Merge remote-tracking branch 'upstream/master'
This commit is contained in:
commit
0b424b00c4
|
@ -1,6 +1,6 @@
|
|||
# Configuration
|
||||
|
||||
Cleanflight is configured primarilty using the Cleanflight Configurator GUI.
|
||||
Cleanflight is configured primarily using the Cleanflight Configurator GUI.
|
||||
|
||||
Both the command line interface and GUI are accessible by connecting to a serial port on the target,
|
||||
be it a USB virtual serial port, physical hardware UART port or a SoftSerial port.
|
||||
|
@ -15,7 +15,7 @@ __Due to ongoing development, the fact that the GUI cannot yet backup all your s
|
|||
|
||||
## GUI
|
||||
|
||||

|
||||

|
||||
|
||||
The GUI tool is the preferred way of configuration. The GUI tool also includes a terminal which
|
||||
can be used to interact with the CLI.
|
||||
|
|
Before Width: | Height: | Size: 70 KiB After Width: | Height: | Size: 70 KiB |
|
@ -16,6 +16,8 @@ This project could really do with some functional tests which test the behaviour
|
|||
|
||||
All pull requests to add/improve the testability of the code or testing methods are highly sought!
|
||||
|
||||
Note: Tests are written in C++ and linked with with firmware's C code.
|
||||
|
||||
##General principals
|
||||
|
||||
1. Name everything well.
|
||||
|
@ -48,22 +50,3 @@ You can run them on the command line to execute the tests and to see the test re
|
|||
You can also step-debug the tests in eclipse and you can use the GoogleTest test runner to make building and re-running the tests simple.
|
||||
|
||||
The tests are currently always compiled with debugging information enabled, there may be additional warnings, if you see any warnings please attempt to fix them and submit pull requests with the fixes.
|
||||
|
||||
|
||||
##TODO
|
||||
|
||||
* Test OpenLRSNG's RSSI PWM on AUX5-8.
|
||||
* Add support for UART3/4 on STM32F3.
|
||||
* Cleanup validateAndFixConfig and pwm_mapping.c to use some kind of feature/timer/io pin mapping to remove #ifdef
|
||||
* Split RX config into RC config and RX config.
|
||||
* Enabling/disabling features should not take effect until reboot since. Main loop executes and uses new flags as they are set in the cli but
|
||||
appropriate init methods will not have been called which results in undefined behaviour and could damage connected devices - this is a legacy
|
||||
problem from baseflight.
|
||||
* Solve all the naze rev4/5 HSE_VALUE == 8000000/1200000 checking, the checks should only apply to the naze32 target. See system_stm32f10x.c/SetSysClock().
|
||||
|
||||
##Known Issues
|
||||
|
||||
* Softserial RX on STM32F3 does not work. TX is fine.
|
||||
* Dynamic throttle PID does not work with new pid controller.
|
||||
* Autotune does not work yet with with new pid controller.
|
||||
|
||||
|
|
|
@ -82,6 +82,9 @@
|
|||
|
||||
#define ARRAY_LENGTH(x) (sizeof((x))/sizeof((x)[0]))
|
||||
|
||||
#define STATIC_ASSERT(condition, name ) \
|
||||
typedef char assert_failed_ ## name [(condition) ? 1 : -1 ]
|
||||
|
||||
// Some macros to make writing FLIGHT_LOG_FIELD_* constants shorter:
|
||||
#define STR_HELPER(x) #x
|
||||
#define STR(x) STR_HELPER(x)
|
||||
|
@ -234,7 +237,8 @@ typedef enum BlackboxState {
|
|||
BLACKBOX_STATE_SEND_GPS_G_HEADERS,
|
||||
BLACKBOX_STATE_SEND_SYSINFO,
|
||||
BLACKBOX_STATE_PRERUN,
|
||||
BLACKBOX_STATE_RUNNING
|
||||
BLACKBOX_STATE_RUNNING,
|
||||
BLACKBOX_STATE_SHUTTING_DOWN
|
||||
} BlackboxState;
|
||||
|
||||
typedef struct gpsState_t {
|
||||
|
@ -266,8 +270,11 @@ static struct {
|
|||
} u;
|
||||
} xmitState;
|
||||
|
||||
// Cache for FLIGHT_LOG_FIELD_CONDITION_* test results:
|
||||
static uint32_t blackboxConditionCache;
|
||||
|
||||
STATIC_ASSERT((sizeof(blackboxConditionCache) * 8) >= FLIGHT_LOG_FIELD_CONDITION_NEVER, too_many_flight_log_conditions);
|
||||
|
||||
static uint32_t blackboxIteration;
|
||||
static uint32_t blackboxPFrameIndex, blackboxIFrameIndex;
|
||||
|
||||
|
@ -670,6 +677,9 @@ static void blackboxSetState(BlackboxState newState)
|
|||
blackboxPFrameIndex = 0;
|
||||
blackboxIFrameIndex = 0;
|
||||
break;
|
||||
case BLACKBOX_STATE_SHUTTING_DOWN:
|
||||
xmitState.u.startTime = millis();
|
||||
break;
|
||||
default:
|
||||
;
|
||||
}
|
||||
|
@ -893,6 +903,14 @@ static void releaseBlackboxPort(void)
|
|||
serialSetBaudRate(blackboxPort, previousBaudRate);
|
||||
|
||||
endSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX);
|
||||
|
||||
/*
|
||||
* Normally this would be handled by mw.c, but since we take an unknown amount
|
||||
* of time to shut down asynchronously, we're the only ones that know when to call it.
|
||||
*/
|
||||
if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) {
|
||||
mspAllocateSerialPorts(&masterConfig.serialConfig);
|
||||
}
|
||||
}
|
||||
|
||||
void startBlackbox(void)
|
||||
|
@ -930,10 +948,18 @@ void startBlackbox(void)
|
|||
|
||||
void finishBlackbox(void)
|
||||
{
|
||||
if (blackboxState != BLACKBOX_STATE_DISABLED && blackboxState != BLACKBOX_STATE_STOPPED) {
|
||||
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
||||
|
||||
if (blackboxState == BLACKBOX_STATE_RUNNING) {
|
||||
blackboxLogEvent(FLIGHT_LOG_EVENT_LOG_END, NULL);
|
||||
|
||||
blackboxSetState(BLACKBOX_STATE_SHUTTING_DOWN);
|
||||
} else if (blackboxState != BLACKBOX_STATE_DISABLED && blackboxState != BLACKBOX_STATE_STOPPED
|
||||
&& blackboxState != BLACKBOX_STATE_SHUTTING_DOWN) {
|
||||
/*
|
||||
* We're shutting down in the middle of transmitting headers, so we can't log a "log completed" event.
|
||||
* Just give the port back and stop immediately.
|
||||
*/
|
||||
releaseBlackboxPort();
|
||||
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1140,7 +1166,6 @@ static bool blackboxWriteSysinfo()
|
|||
blackboxPrintf("H P interval:%d/%d\n", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H P interval:%d/%d\n");
|
||||
|
||||
break;
|
||||
case 5:
|
||||
blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
|
||||
|
@ -1162,10 +1187,10 @@ static bool blackboxWriteSysinfo()
|
|||
blackboxPrintf("H gyro.scale:0x%x\n", floatConvert.u);
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H gyro.scale:0x%x\n") + 6;
|
||||
break;
|
||||
break;
|
||||
case 9:
|
||||
blackboxPrintf("H acc_1G:%u\n", acc_1G);
|
||||
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H acc_1G:%u\n");
|
||||
break;
|
||||
case 10:
|
||||
|
@ -1223,7 +1248,7 @@ void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data)
|
|||
blackboxWrite(data->autotuneCycleStart.d);
|
||||
break;
|
||||
case FLIGHT_LOG_EVENT_LOG_END:
|
||||
blackboxPrint("That's all folks!");
|
||||
blackboxPrint("End of log");
|
||||
blackboxWrite(0);
|
||||
break;
|
||||
}
|
||||
|
@ -1352,6 +1377,20 @@ void handleBlackbox(void)
|
|||
blackboxIFrameIndex++;
|
||||
}
|
||||
break;
|
||||
case BLACKBOX_STATE_SHUTTING_DOWN:
|
||||
//On entry of this state, startTime is set
|
||||
|
||||
/*
|
||||
* Wait for the log we've transmitted to make its way to the logger before we release the serial port,
|
||||
* since releasing the port clears the Tx buffer.
|
||||
*
|
||||
* Don't wait longer than it could possibly take if something funky happens.
|
||||
*/
|
||||
if (millis() > xmitState.u.startTime + 200 || isSerialTransmitBufferEmpty(blackboxPort)) {
|
||||
releaseBlackboxPort();
|
||||
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -69,7 +69,7 @@ static void putchw(void *putp, putcf putf, int n, char z, char *bf)
|
|||
putf(putp, ch);
|
||||
}
|
||||
|
||||
void tfp_format(void *putp, putcf putf, char *fmt, va_list va)
|
||||
void tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
|
||||
{
|
||||
char bf[12];
|
||||
|
||||
|
@ -154,7 +154,7 @@ void init_printf(void *putp, void (*putf) (void *, char))
|
|||
stdout_putp = putp;
|
||||
}
|
||||
|
||||
void tfp_printf(char *fmt, ...)
|
||||
void tfp_printf(const char *fmt, ...)
|
||||
{
|
||||
va_list va;
|
||||
va_start(va, fmt);
|
||||
|
@ -168,7 +168,7 @@ static void putcp(void *p, char c)
|
|||
*(*((char **) p))++ = c;
|
||||
}
|
||||
|
||||
void tfp_sprintf(char *s, char *fmt, ...)
|
||||
void tfp_sprintf(char *s, const char *fmt, ...)
|
||||
{
|
||||
va_list va;
|
||||
|
||||
|
|
|
@ -107,10 +107,10 @@ regs Kusti, 23.10.2004
|
|||
|
||||
void init_printf(void *putp, void (*putf) (void *, char));
|
||||
|
||||
void tfp_printf(char *fmt, ...);
|
||||
void tfp_sprintf(char *s, char *fmt, ...);
|
||||
void tfp_printf(const char *fmt, ...);
|
||||
void tfp_sprintf(char *s, const char *fmt, ...);
|
||||
|
||||
void tfp_format(void *putp, void (*putf) (void *, char), char *fmt, va_list va);
|
||||
void tfp_format(void *putp, void (*putf) (void *, char), const char *fmt, va_list va);
|
||||
|
||||
#define printf tfp_printf
|
||||
#define sprintf tfp_sprintf
|
||||
|
|
|
@ -90,7 +90,7 @@ int a2d(char ch)
|
|||
return -1;
|
||||
}
|
||||
|
||||
char a2i(char ch, char **src, int base, int *nump)
|
||||
char a2i(char ch, const char **src, int base, int *nump)
|
||||
{
|
||||
char *p = *src;
|
||||
int num = 0;
|
||||
|
|
|
@ -20,7 +20,7 @@ void uli2a(unsigned long int num, unsigned int base, int uc, char *bf);
|
|||
void li2a(long num, char *bf);
|
||||
void ui2a(unsigned int num, unsigned int base, int uc, char *bf);
|
||||
void i2a(int num, char *bf);
|
||||
char a2i(char ch, char **src, int base, int *nump);
|
||||
char a2i(char ch, const char **src, int base, int *nump);
|
||||
char *ftoa(float x, char *floatString);
|
||||
float fastA2F(const char *p);
|
||||
|
||||
|
|
|
@ -378,24 +378,28 @@ void showBatteryPage(void)
|
|||
void showSensorsPage(void)
|
||||
{
|
||||
uint8_t rowIndex = PAGE_TITLE_LINE_COUNT;
|
||||
static const char *format = "%c = %5d %5d %5d";
|
||||
|
||||
i2c_OLED_set_line(rowIndex++);
|
||||
i2c_OLED_send_string(" X Y Z");
|
||||
|
||||
if (sensors(SENSOR_ACC)) {
|
||||
tfp_sprintf(lineBuffer, "A = %5d %5d %5d", accSmooth[X], accSmooth[Y], accSmooth[Z]);
|
||||
tfp_sprintf(lineBuffer, format, 'A', accSmooth[X], accSmooth[Y], accSmooth[Z]);
|
||||
padLineBuffer();
|
||||
i2c_OLED_set_line(rowIndex++);
|
||||
i2c_OLED_send_string(lineBuffer);
|
||||
}
|
||||
|
||||
if (sensors(SENSOR_GYRO)) {
|
||||
tfp_sprintf(lineBuffer, "G = %5d %5d %5d", gyroADC[X], gyroADC[Y], gyroADC[Z]);
|
||||
tfp_sprintf(lineBuffer, format, 'G', gyroADC[X], gyroADC[Y], gyroADC[Z]);
|
||||
padLineBuffer();
|
||||
i2c_OLED_set_line(rowIndex++);
|
||||
i2c_OLED_send_string(lineBuffer);
|
||||
}
|
||||
|
||||
#ifdef MAG
|
||||
if (sensors(SENSOR_MAG)) {
|
||||
tfp_sprintf(lineBuffer, "M = %5d %5d %5d", magADC[X], magADC[Y], magADC[Z]);
|
||||
tfp_sprintf(lineBuffer, format, 'M', magADC[X], magADC[Y], magADC[Z]);
|
||||
padLineBuffer();
|
||||
i2c_OLED_set_line(rowIndex++);
|
||||
i2c_OLED_send_string(lineBuffer);
|
||||
|
|
|
@ -50,14 +50,26 @@
|
|||
static bool ledStripInitialised = false;
|
||||
static failsafe_t* failsafe;
|
||||
|
||||
//#define USE_LED_ANIMATION
|
||||
|
||||
// timers
|
||||
#ifdef USE_LED_ANIMATION
|
||||
static uint32_t nextAnimationUpdateAt = 0;
|
||||
#endif
|
||||
|
||||
static uint32_t nextIndicatorFlashAt = 0;
|
||||
static uint32_t nextWarningFlashAt = 0;
|
||||
|
||||
#define LED_STRIP_20HZ ((1000 * 1000) / 20)
|
||||
#define LED_STRIP_10HZ ((1000 * 1000) / 10)
|
||||
#define LED_STRIP_5HZ ((1000 * 1000) / 5)
|
||||
|
||||
#if MAX_LED_STRIP_LENGTH > WS2811_LED_STRIP_LENGTH
|
||||
#error "Led strip length must match driver"
|
||||
#endif
|
||||
|
||||
hsvColor_t *colors;
|
||||
|
||||
//#define USE_LED_ANIMATION
|
||||
|
||||
// H S V
|
||||
#define LED_BLACK { 0, 0, 0}
|
||||
#define LED_WHITE { 0, 255, 255}
|
||||
|
@ -185,6 +197,7 @@ static const modeColorIndexes_t angleModeColors = {
|
|||
COLOR_ORANGE
|
||||
};
|
||||
|
||||
#ifdef MAG
|
||||
static const modeColorIndexes_t magModeColors = {
|
||||
COLOR_MINT_GREEN,
|
||||
COLOR_DARK_VIOLET,
|
||||
|
@ -193,6 +206,7 @@ static const modeColorIndexes_t magModeColors = {
|
|||
COLOR_BLUE,
|
||||
COLOR_ORANGE
|
||||
};
|
||||
#endif
|
||||
|
||||
static const modeColorIndexes_t baroModeColors = {
|
||||
COLOR_LIGHT_BLUE,
|
||||
|
@ -436,15 +450,6 @@ void generateLedConfig(uint8_t ledIndex, char *ledConfigBuffer, size_t bufferSiz
|
|||
sprintf(ledConfigBuffer, "%u,%u:%s:%s", GET_LED_X(ledConfig), GET_LED_Y(ledConfig), directions, functions);
|
||||
}
|
||||
|
||||
// timers
|
||||
uint32_t nextAnimationUpdateAt = 0;
|
||||
uint32_t nextIndicatorFlashAt = 0;
|
||||
uint32_t nextWarningFlashAt = 0;
|
||||
|
||||
#define LED_STRIP_20HZ ((1000 * 1000) / 20)
|
||||
#define LED_STRIP_10HZ ((1000 * 1000) / 10)
|
||||
#define LED_STRIP_5HZ ((1000 * 1000) / 5)
|
||||
|
||||
void applyDirectionalModeColor(const uint8_t ledIndex, const ledConfig_t *ledConfig, const modeColorIndexes_t *modeColors)
|
||||
{
|
||||
// apply up/down colors regardless of quadrant.
|
||||
|
@ -686,6 +691,7 @@ void applyLedThrottleLayer()
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef USE_LED_ANIMATION
|
||||
static uint8_t frameCounter = 0;
|
||||
|
||||
static uint8_t previousRow;
|
||||
|
@ -703,7 +709,6 @@ static void updateLedAnimationState(void)
|
|||
frameCounter = (frameCounter + 1) % animationFrames;
|
||||
}
|
||||
|
||||
#ifdef USE_LED_ANIMATION
|
||||
static void applyLedAnimationLayer(void)
|
||||
{
|
||||
const ledConfig_t *ledConfig;
|
||||
|
@ -738,11 +743,18 @@ void updateLedStrip(void)
|
|||
|
||||
uint32_t now = micros();
|
||||
|
||||
bool animationUpdateNow = (int32_t)(now - nextAnimationUpdateAt) >= 0L;
|
||||
bool indicatorFlashNow = (int32_t)(now - nextIndicatorFlashAt) >= 0L;
|
||||
bool warningFlashNow = (int32_t)(now - nextWarningFlashAt) >= 0L;
|
||||
|
||||
if (!(warningFlashNow || indicatorFlashNow || animationUpdateNow)) {
|
||||
bool indicatorFlashNow = indicatorFlashNow = (int32_t)(now - nextIndicatorFlashAt) >= 0L;
|
||||
bool warningFlashNow =warningFlashNow = (int32_t)(now - nextWarningFlashAt) >= 0L;
|
||||
#ifdef USE_LED_ANIMATION
|
||||
bool animationUpdateNow = animationUpdateNow = (int32_t)(now - nextAnimationUpdateAt) >= 0L;
|
||||
#endif
|
||||
if (!(
|
||||
indicatorFlashNow ||
|
||||
warningFlashNow
|
||||
#ifdef USE_LED_ANIMATION
|
||||
|| animationUpdateNow
|
||||
#endif
|
||||
)) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -777,20 +789,21 @@ void updateLedStrip(void)
|
|||
|
||||
applyLedIndicatorLayer(indicatorFlashState);
|
||||
|
||||
#ifdef USE_LED_ANIMATION
|
||||
if (animationUpdateNow) {
|
||||
nextAnimationUpdateAt = now + LED_STRIP_20HZ;
|
||||
updateLedAnimationState();
|
||||
}
|
||||
|
||||
#ifdef USE_LED_ANIMATION
|
||||
applyLedAnimationLayer();
|
||||
#endif
|
||||
|
||||
ws2811UpdateStrip();
|
||||
}
|
||||
|
||||
bool parseColor(uint8_t index, char *colorConfig)
|
||||
bool parseColor(uint8_t index, const char *colorConfig)
|
||||
{
|
||||
char *remainingCharacters = colorConfig;
|
||||
const char *remainingCharacters = colorConfig;
|
||||
|
||||
hsvColor_t *color = &colors[index];
|
||||
|
||||
|
|
|
@ -69,7 +69,7 @@ void updateLedStrip(void);
|
|||
void applyDefaultLedStripConfig(ledConfig_t *ledConfig);
|
||||
void generateLedConfig(uint8_t ledIndex, char *ledConfigBuffer, size_t bufferSize);
|
||||
|
||||
bool parseColor(uint8_t index, char *colorConfig);
|
||||
bool parseColor(uint8_t index, const char *colorConfig);
|
||||
void applyDefaultColors(hsvColor_t *colors, uint8_t colorCount);
|
||||
|
||||
void ledStripEnable(void);
|
||||
|
|
|
@ -311,9 +311,6 @@ void mwDisarm(void)
|
|||
#ifdef BLACKBOX
|
||||
if (feature(FEATURE_BLACKBOX)) {
|
||||
finishBlackbox();
|
||||
if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) {
|
||||
mspAllocateSerialPorts(&masterConfig.serialConfig);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -23,13 +23,23 @@ USER_INCLUDE_DIR = $(USER_DIR)
|
|||
|
||||
OBJECT_DIR = ../../obj/test
|
||||
|
||||
# Flags passed to the preprocessor.
|
||||
# Set Google Test's header directory as a system directory, such that
|
||||
# the compiler doesn't generate warnings in Google Test headers.
|
||||
CPPFLAGS += -isystem $(GTEST_DIR)/inc
|
||||
COMMON_FLAGS = \
|
||||
-g \
|
||||
-Wall \
|
||||
-Wextra \
|
||||
-pthread \
|
||||
-ggdb3 \
|
||||
-O0 \
|
||||
-DUNIT_TEST \
|
||||
-isystem $(GTEST_DIR)/inc
|
||||
|
||||
# Flags passed to the C compiler.
|
||||
C_FLAGS = $(COMMON_FLAGS) \
|
||||
-std=gnu99
|
||||
|
||||
# Flags passed to the C++ compiler.
|
||||
CXXFLAGS += -g -Wall -Wextra -pthread -ggdb3 -O0 -DUNIT_TEST
|
||||
CXX_FLAGS = $(COMMON_FLAGS) \
|
||||
-std=gnu++98
|
||||
|
||||
# All tests produced by this Makefile. Remember to add new tests you
|
||||
# created to the list.
|
||||
|
@ -66,12 +76,12 @@ GTEST_SRCS_ = $(GTEST_DIR)/src/*.cc $(GTEST_DIR)/inc/gtest/*.h $(GTEST_HEADERS)
|
|||
# compiles fast and for ordinary users its source rarely changes.
|
||||
$(OBJECT_DIR)/gtest-all.o : $(GTEST_SRCS_)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) -I$(GTEST_DIR) $(CXXFLAGS) -c \
|
||||
$(CXX) $(CXX_FLAGS) -I$(GTEST_DIR) -c \
|
||||
$(GTEST_DIR)/src/gtest-all.cc -o $@
|
||||
|
||||
$(OBJECT_DIR)/gtest_main.o : $(GTEST_SRCS_)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) -I$(GTEST_DIR) $(CXXFLAGS) -c \
|
||||
$(CXX) $(CXX_FLAGS) -I$(GTEST_DIR) -c \
|
||||
$(GTEST_DIR)/src/gtest_main.cc -o $@
|
||||
|
||||
$(OBJECT_DIR)/gtest.a : $(OBJECT_DIR)/gtest-all.o
|
||||
|
@ -87,118 +97,209 @@ $(OBJECT_DIR)/gtest_main.a : $(OBJECT_DIR)/gtest-all.o $(OBJECT_DIR)/gtest_main.
|
|||
# includes in test dir must override includes in user dir
|
||||
TEST_INCLUDE_DIRS := $(TEST_DIR) \
|
||||
$(USER_INCLUDE_DIR)
|
||||
|
||||
|
||||
TEST_CFLAGS = $(addprefix -I,$(TEST_INCLUDE_DIRS))
|
||||
|
||||
$(OBJECT_DIR)/common/maths.o : \
|
||||
$(USER_DIR)/common/maths.c \
|
||||
$(USER_DIR)/common/maths.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/common/maths.c -o $@
|
||||
|
||||
|
||||
$(OBJECT_DIR)/sensors/battery.o : $(USER_DIR)/sensors/battery.c $(USER_DIR)/sensors/battery.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/sensors/battery.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/sensors/battery.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/battery_unittest.o : \
|
||||
$(TEST_DIR)/battery_unittest.cc \
|
||||
$(USER_DIR)/sensors/battery.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/battery_unittest.o : $(TEST_DIR)/battery_unittest.cc \
|
||||
$(USER_DIR)/sensors/battery.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/battery_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/battery_unittest.cc -o $@
|
||||
|
||||
battery_unittest : $(OBJECT_DIR)/sensors/battery.o $(OBJECT_DIR)/battery_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
battery_unittest : \
|
||||
$(OBJECT_DIR)/sensors/battery.o \
|
||||
$(OBJECT_DIR)/common/maths.o \
|
||||
$(OBJECT_DIR)/battery_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
$(OBJECT_DIR)/flight/imu.o : \
|
||||
$(USER_DIR)/flight/imu.c \
|
||||
$(USER_DIR)/flight/imu.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/flight/imu.o : $(USER_DIR)/flight/imu.c $(USER_DIR)/flight/imu.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/imu.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/imu.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/flight_imu_unittest.o : \
|
||||
$(TEST_DIR)/flight_imu_unittest.cc \
|
||||
$(USER_DIR)/flight/imu.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/flight_imu_unittest.o : $(TEST_DIR)/flight_imu_unittest.cc \
|
||||
$(USER_DIR)/flight/imu.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/flight_imu_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/flight_imu_unittest.cc -o $@
|
||||
|
||||
flight_imu_unittest : $(OBJECT_DIR)/flight/imu.o $(OBJECT_DIR)/flight/altitudehold.o $(OBJECT_DIR)/flight_imu_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
flight_imu_unittest : \
|
||||
$(OBJECT_DIR)/flight/imu.o \
|
||||
$(OBJECT_DIR)/flight/altitudehold.o \
|
||||
$(OBJECT_DIR)/flight_imu_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
||||
$(OBJECT_DIR)/flight/altitudehold.o : $(USER_DIR)/flight/altitudehold.c $(USER_DIR)/flight/altitudehold.h $(GTEST_HEADERS)
|
||||
$(OBJECT_DIR)/flight/altitudehold.o : \
|
||||
$(USER_DIR)/flight/altitudehold.c \
|
||||
$(USER_DIR)/flight/altitudehold.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/altitudehold.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/altitudehold.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/altitude_hold_unittest.o : \
|
||||
$(TEST_DIR)/altitude_hold_unittest.cc \
|
||||
$(USER_DIR)/flight/altitudehold.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/altitude_hold_unittest.o : $(TEST_DIR)/altitude_hold_unittest.cc \
|
||||
$(USER_DIR)/flight/altitudehold.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/altitude_hold_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/altitude_hold_unittest.cc -o $@
|
||||
|
||||
altitude_hold_unittest : $(OBJECT_DIR)/flight/altitudehold.o $(OBJECT_DIR)/altitude_hold_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
altitude_hold_unittest : \
|
||||
$(OBJECT_DIR)/flight/altitudehold.o \
|
||||
$(OBJECT_DIR)/altitude_hold_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
$(OBJECT_DIR)/flight/gps_conversion.o : \
|
||||
$(USER_DIR)/flight/gps_conversion.c \
|
||||
$(USER_DIR)/flight/gps_conversion.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/flight/gps_conversion.o : $(USER_DIR)/flight/gps_conversion.c $(USER_DIR)/flight/gps_conversion.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/gps_conversion.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/gps_conversion.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/gps_conversion_unittest.o : \
|
||||
$(TEST_DIR)/gps_conversion_unittest.cc \
|
||||
$(USER_DIR)/flight/gps_conversion.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/gps_conversion_unittest.o : $(TEST_DIR)/gps_conversion_unittest.cc \
|
||||
$(USER_DIR)/flight/gps_conversion.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/gps_conversion_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/gps_conversion_unittest.cc -o $@
|
||||
|
||||
gps_conversion_unittest : $(OBJECT_DIR)/flight/gps_conversion.o $(OBJECT_DIR)/gps_conversion_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
gps_conversion_unittest : \
|
||||
$(OBJECT_DIR)/flight/gps_conversion.o \
|
||||
$(OBJECT_DIR)/gps_conversion_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
||||
$(OBJECT_DIR)/telemetry/hott.o : $(USER_DIR)/telemetry/hott.c $(USER_DIR)/telemetry/hott.h $(GTEST_HEADERS)
|
||||
$(OBJECT_DIR)/telemetry/hott.o : \
|
||||
$(USER_DIR)/telemetry/hott.c \
|
||||
$(USER_DIR)/telemetry/hott.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/telemetry/hott.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/telemetry/hott.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/telemetry_hott_unittest.o : $(TEST_DIR)/telemetry_hott_unittest.cc \
|
||||
$(USER_DIR)/telemetry/hott.h $(GTEST_HEADERS)
|
||||
$(OBJECT_DIR)/telemetry_hott_unittest.o : \
|
||||
$(TEST_DIR)/telemetry_hott_unittest.cc \
|
||||
$(USER_DIR)/telemetry/hott.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/telemetry_hott_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/telemetry_hott_unittest.cc -o $@
|
||||
|
||||
telemetry_hott_unittest :$(OBJECT_DIR)/telemetry/hott.o $(OBJECT_DIR)/telemetry_hott_unittest.o $(OBJECT_DIR)/flight/gps_conversion.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
telemetry_hott_unittest : \
|
||||
$(OBJECT_DIR)/telemetry/hott.o \
|
||||
$(OBJECT_DIR)/telemetry_hott_unittest.o \
|
||||
$(OBJECT_DIR)/flight/gps_conversion.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
||||
$(OBJECT_DIR)/io/rc_controls.o : $(USER_DIR)/io/rc_controls.c $(USER_DIR)/io/rc_controls.h $(GTEST_HEADERS)
|
||||
$(OBJECT_DIR)/io/rc_controls.o : \
|
||||
$(USER_DIR)/io/rc_controls.c \
|
||||
$(USER_DIR)/io/rc_controls.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/rc_controls.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/rc_controls.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/rc_controls_unittest.o : \
|
||||
$(TEST_DIR)/rc_controls_unittest.cc \
|
||||
$(USER_DIR)/io/rc_controls.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/rc_controls_unittest.o : $(TEST_DIR)/rc_controls_unittest.cc \
|
||||
$(USER_DIR)/io/rc_controls.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/rc_controls_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/rc_controls_unittest.cc -o $@
|
||||
|
||||
rc_controls_unittest :$(OBJECT_DIR)/io/rc_controls.o $(OBJECT_DIR)/rc_controls_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
rc_controls_unittest : \
|
||||
$(OBJECT_DIR)/io/rc_controls.o \
|
||||
$(OBJECT_DIR)/rc_controls_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
$(OBJECT_DIR)/io/ledstrip.o : $(USER_DIR)/io/ledstrip.c $(USER_DIR)/io/ledstrip.h $(GTEST_HEADERS)
|
||||
$(OBJECT_DIR)/io/ledstrip.o : \
|
||||
$(USER_DIR)/io/ledstrip.c \
|
||||
$(USER_DIR)/io/ledstrip.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/ledstrip.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/ledstrip.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/ledstrip_unittest.o : \
|
||||
$(TEST_DIR)/ledstrip_unittest.cc \
|
||||
$(USER_DIR)/io/ledstrip.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/ledstrip_unittest.o : $(TEST_DIR)/ledstrip_unittest.cc \
|
||||
$(USER_DIR)/io/ledstrip.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/ledstrip_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/ledstrip_unittest.cc -o $@
|
||||
|
||||
ledstrip_unittest :$(OBJECT_DIR)/io/ledstrip.o $(OBJECT_DIR)/ledstrip_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
ledstrip_unittest : \
|
||||
$(OBJECT_DIR)/io/ledstrip.o \
|
||||
$(OBJECT_DIR)/ledstrip_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
||||
$(OBJECT_DIR)/drivers/light_ws2811strip.o : $(USER_DIR)/drivers/light_ws2811strip.c $(USER_DIR)/drivers/light_ws2811strip.h $(GTEST_HEADERS)
|
||||
$(OBJECT_DIR)/drivers/light_ws2811strip.o : \
|
||||
$(USER_DIR)/drivers/light_ws2811strip.c \
|
||||
$(USER_DIR)/drivers/light_ws2811strip.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/light_ws2811strip.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/light_ws2811strip.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/ws2811_unittest.o : \
|
||||
$(TEST_DIR)/ws2811_unittest.cc \
|
||||
$(USER_DIR)/drivers/light_ws2811strip.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/ws2811_unittest.o : $(TEST_DIR)/ws2811_unittest.cc \
|
||||
$(USER_DIR)/drivers/light_ws2811strip.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/ws2811_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/ws2811_unittest.cc -o $@
|
||||
|
||||
ws2811_unittest :$(OBJECT_DIR)/drivers/light_ws2811strip.o $(OBJECT_DIR)/ws2811_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
ws2811_unittest : \
|
||||
$(OBJECT_DIR)/drivers/light_ws2811strip.o \
|
||||
$(OBJECT_DIR)/ws2811_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
|
|
@ -27,7 +27,9 @@ extern "C" {
|
|||
#include "flight/flight.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/compass.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/acceleration.h"
|
||||
|
|
|
@ -18,7 +18,10 @@
|
|||
#include <stdint.h>
|
||||
|
||||
#include <limits.h>
|
||||
#include "flight/gps_conversion.h"
|
||||
|
||||
extern "C" {
|
||||
#include "flight/gps_conversion.h"
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
@ -33,7 +36,7 @@ TEST(GpsConversionTest, GPSCoordToDegrees_BadString)
|
|||
}
|
||||
|
||||
typedef struct gpsConversionExpectation_s {
|
||||
char *coord;
|
||||
const char *coord;
|
||||
uint32_t degrees;
|
||||
} gpsConversionExpectation_t;
|
||||
|
||||
|
|
|
@ -19,37 +19,40 @@
|
|||
|
||||
#include <limits.h>
|
||||
|
||||
#include "build_config.h"
|
||||
extern "C" {
|
||||
#include "build_config.h"
|
||||
|
||||
#include "common/color.h"
|
||||
#include "common/axis.h"
|
||||
#include "flight/flight.h"
|
||||
#include "common/color.h"
|
||||
#include "common/axis.h"
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
#include "io/ledstrip.h"
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
extern ledConfig_t *ledConfigs;
|
||||
extern uint8_t highestYValueForNorth;
|
||||
extern uint8_t lowestYValueForSouth;
|
||||
extern uint8_t highestXValueForWest;
|
||||
extern uint8_t lowestXValueForEast;
|
||||
extern uint8_t ledGridWidth;
|
||||
extern uint8_t ledGridHeight;
|
||||
extern "C" {
|
||||
extern ledConfig_t *ledConfigs;
|
||||
extern uint8_t highestYValueForNorth;
|
||||
extern uint8_t lowestYValueForSouth;
|
||||
extern uint8_t highestXValueForWest;
|
||||
extern uint8_t lowestXValueForEast;
|
||||
extern uint8_t ledGridWidth;
|
||||
extern uint8_t ledGridHeight;
|
||||
|
||||
void determineLedStripDimensions(void);
|
||||
void determineOrientationLimits(void);
|
||||
void determineLedStripDimensions(void);
|
||||
void determineOrientationLimits(void);
|
||||
|
||||
ledConfig_t systemLedConfigs[MAX_LED_STRIP_LENGTH];
|
||||
ledConfig_t systemLedConfigs[MAX_LED_STRIP_LENGTH];
|
||||
}
|
||||
|
||||
TEST(LedStripTest, parseLedStripConfig)
|
||||
{
|
||||
|
@ -312,7 +315,7 @@ TEST(ColorTest, parseColor)
|
|||
{ 333, 22, 1 }
|
||||
};
|
||||
|
||||
char *testColors[TEST_COLOR_COUNT] = {
|
||||
const char *testColors[TEST_COLOR_COUNT] = {
|
||||
"0,0,0",
|
||||
"1,1,1",
|
||||
"359,255,255",
|
||||
|
@ -336,12 +339,18 @@ TEST(ColorTest, parseColor)
|
|||
}
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
|
||||
uint8_t armingFlags = 0;
|
||||
uint16_t flightModeFlags = 0;
|
||||
int16_t rcCommand[4];
|
||||
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||
|
||||
batteryState_e calculateBatteryState(void) {
|
||||
return BATTERY_OK;
|
||||
}
|
||||
|
||||
void ws2811LedStripInit(void) {}
|
||||
void ws2811UpdateStrip(void) {}
|
||||
|
||||
void setLedValue(uint16_t index, const uint8_t value) {
|
||||
|
@ -399,3 +408,5 @@ int scaleRange(int x, int srcMin, int srcMax, int destMin, int destMax) {
|
|||
|
||||
return 0;
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define MAG
|
||||
#define BARO
|
||||
#define GPS
|
||||
#define TELEMETRY
|
||||
|
|
|
@ -19,23 +19,27 @@
|
|||
|
||||
#include <limits.h>
|
||||
|
||||
#include "build_config.h"
|
||||
extern "C" {
|
||||
#include "build_config.h"
|
||||
|
||||
#include "common/color.h"
|
||||
#include "common/color.h"
|
||||
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
extern "C" {
|
||||
STATIC_UNIT_TESTED extern uint16_t dmaBufferOffset;
|
||||
|
||||
STATIC_UNIT_TESTED void fastUpdateLEDDMABuffer(rgbColor24bpp_t *color);
|
||||
STATIC_UNIT_TESTED void updateLEDDMABuffer(uint8_t componentValue);
|
||||
}
|
||||
|
||||
TEST(WS2812, updateDMABuffer) {
|
||||
// given
|
||||
rgbColor24bpp_t color1 = {0xFF,0xAA,0x55};
|
||||
rgbColor24bpp_t color1 = { .raw = {0xFF,0xAA,0x55} };
|
||||
|
||||
// and
|
||||
dmaBufferOffset = 0;
|
||||
|
@ -86,6 +90,7 @@ TEST(WS2812, updateDMABuffer) {
|
|||
byteIndex++;
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
rgbColor24bpp_t* hsvToRgb24(const hsvColor_t *c) {
|
||||
UNUSED(c);
|
||||
return NULL;
|
||||
|
@ -93,3 +98,4 @@ rgbColor24bpp_t* hsvToRgb24(const hsvColor_t *c) {
|
|||
|
||||
void ws2811LedStripHardwareInit(void) {}
|
||||
void ws2811LedStripDMAEnable(void) {}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue