1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-14 03:50:02 +03:00

Improve unittest build system (#13554)

* unittest - fix duplicate symbols in unittests

Some symbols were declared again
With clang -fcommon, this resulted in allocatin in common segment and
prevented error.
(tentative definitions in C standard).
-fno-common (now default in clang https://reviews.llvm.org/D75056)
causes compilation errors.

Declarations are now marked extern.

* unittest - fix scheduler array size for unittest

Unittest needs extra space for canary

* unittest - fix missing include (needed for clang-16)

* unittest - remove unused varibles

-Werror in clang 15+

* unittest - increase max supported version to clang-16

* unittest - conditionaly disable useless output in unittests

* unittest - C++11 version of STATIC_ASSERT

* unittest - fix initializers for g++

- Change order of initializers to match order in struct
- make valueTable initializion consistent (necessary for C++)
- adapt controlRateConfig

* unittest - adapt scheduler_unitest for g++

scheduler_stubs.c is necessary to initialize task_attributes

* unittest - fix ledstrip unittest

only part of config was zeroed

* unittest - fix g++ warnings

- memcpy when length is known and \0 is not copied
- isError is local stub, no extern
- serialReadStub - don't memcpy into object, use initializer

* cli - cleanup cliGetSettingIndex

- compare only passed bytes (old version may read data after
name)
- input string is const

* unittest - fix ld warning from PG sections

move pg data sections after .rodata. Sections were marked as writable
due to relocation (!?). That marked .text output section
(containing .pg_data) as writable too and linker correctly complained
that executable section is writable.

* unittest - cleanup

* unittest - adapt after code cleanup, add gcc

- remove clang flags that are not necessary now (tested on clang-11
and clang-16)
- add support for gcc ( make test CC=gcc CXX=g++ )
- add suport for different optimization level (detects some code
problems) : make test OPTIMIZE=-O2
- fallback to clang on Linux too

* fixup! unittest - conditionaly disable useless output in unittests
This commit is contained in:
Petr Ledvina 2024-04-22 22:43:24 +02:00 committed by GitHub
parent d20d42dd48
commit d447d795f4
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
17 changed files with 247 additions and 179 deletions

View file

@ -4384,13 +4384,13 @@ static uint8_t getWordLength(char *bufBegin, char *bufEnd)
return bufEnd - bufBegin;
}
uint16_t cliGetSettingIndex(char *name, uint8_t length)
uint16_t cliGetSettingIndex(const char *name, size_t length)
{
for (uint32_t i = 0; i < valueTableEntryCount; i++) {
const char *settingName = valueTable[i].name;
// ensure exact match when setting to prevent setting variables with shorter names
if (strncasecmp(name, settingName, strlen(settingName)) == 0 && length == strlen(settingName)) {
// ensure exact match when setting to prevent setting variables with longer names
if (strncasecmp(name, settingName, length) == 0 && length == strlen(settingName)) {
return i;
}
}
@ -4580,7 +4580,7 @@ STATIC_UNIT_TESTED void cliSet(const char *cmdName, char *cmdline)
if (updatable && len > 0 && len <= max) {
memset((char *)cliGetValuePointer(val), 0, max);
if (len >= min && strncmp(valPtr, emptyName, len)) {
strncpy((char *)cliGetValuePointer(val), valPtr, len);
memcpy((char *)cliGetValuePointer(val), valPtr, len);
}
valueChanged = true;
} else {

View file

@ -60,8 +60,12 @@
#define DISCARD(x) (void)(x) // To explicitly ignore result of x (usually an I/O register access).
#ifndef __cplusplus
#define STATIC_ASSERT(condition, name) _Static_assert((condition), #name)
#else
// since C++11
#define STATIC_ASSERT(condition, name) static_assert((condition), #name)
#endif
#define BIT(x) (1 << (x))

View file

@ -127,10 +127,10 @@ extern const uint8_t __pg_resetdata_end[];
.length = 1, \
.size = sizeof(_type) | PGR_SIZE_SYSTEM_FLAG, \
.address = (uint8_t*)&_name ## _System, \
.fnv_hash = &_name ## _fnv_hash, \
.copy = (uint8_t*)&_name ## _Copy, \
.ptr = 0, \
_reset, \
.fnv_hash = &_name ## _fnv_hash, \
} \
/**/
@ -159,10 +159,10 @@ extern const uint8_t __pg_resetdata_end[];
.length = _length, \
.size = (sizeof(_type) * _length) | PGR_SIZE_SYSTEM_FLAG, \
.address = (uint8_t*)&_name ## _SystemArray, \
.fnv_hash = &_name ## _fnv_hash, \
.copy = (uint8_t*)&_name ## _CopyArray, \
.ptr = 0, \
_reset, \
.fnv_hash = &_name ## _fnv_hash, \
} \
/**/

View file

@ -293,7 +293,8 @@ rx_sumd_unittest_SRC := \
scheduler_unittest_SRC := \
$(USER_DIR)/scheduler/scheduler.c \
$(USER_DIR)/common/crc.c \
$(USER_DIR)/common/streambuf.c
$(USER_DIR)/common/streambuf.c \
$(TEST_DIR)/scheduler_stubs.c
scheduler_unittest_DEFINES := \
USE_OSD=
@ -483,33 +484,21 @@ GTEST_DIR = ../../lib/test/gtest
CC := clang-12
CXX := clang++-12
ifneq ($(OSFAMILY), linux)
ifeq ($(shell which $(CC) 2>/dev/null),)
$(info Falling back to 'clang' on Windows and OSX.)
$(info Falling back to 'clang')
CC := clang
CXX := clang++
endif
endif
#CC := gcc
#CXX := g++
# These flags are needed for clang > 10 (linux / MacOS) to make test work:
# -Wno-c99-extensions
# -Wno-reorder
OPTIMIZE = -O0
COMMON_FLAGS = \
-g \
-Wall \
-Wextra \
-Werror \
-Wno-error=unused-command-line-argument \
-ggdb3 \
-O0 \
-g -ggdb3 \
-Wall -Wextra \
$(OPTIMIZE) \
-DUNIT_TEST \
-isystem $(GTEST_DIR)/inc \
-MMD -MP \
-Wno-c99-extensions \
-Wno-reorder \
-pipe
CC_VERSION = $(shell $(CC) -dumpversion)
@ -523,12 +512,11 @@ CC_VERSION_MAJOR := $(firstword $(subst ., ,$(CC_VERSION)))
CC_VERSION_CHECK_MIN := 7
CC_VERSION_CHECK_MAX := 16
# Added flags for clang 11 - 13 are not backwards compatible
ifeq ($(shell expr $(CC_VERSION_MAJOR) \> 10 \& $(CC_VERSION_MAJOR) \< 14), 1)
COMMON_FLAGS += \
-fcommon \
-Wno-void-pointer-to-int-cast
endif
# c99-designator is fine, code is not expected to be clean C++
COMMON_FLAGS += -Wno-c99-designator
# no warning expected on clang
COMMON_FLAGS += -Werror
ifeq ($(shell expr $(CC_VERSION_MAJOR) \< $(CC_VERSION_CHECK_MIN) \| $(CC_VERSION_MAJOR) \> $(CC_VERSION_CHECK_MAX)),1)
$(error $(CC) $(CC_VERSION) is not supported. The officially supported version of clang is 'clang-12'. If this is not found, 'clang' is used as a fallback. The version of the compiler must be between $(CC_VERSION_CHECK_MIN) and $(CC_VERSION_CHECK_MAX).)
@ -538,9 +526,17 @@ COMMON_FLAGS += -fblocks
ifndef CYGWIN
ifneq ($(OSFAMILY), macosx)
LDFLAGS += -lBlocksRuntime
endif
endif
endif
endif # !macosx
endif # !CYGWIN
else ifeq ($(shell $(CC) -v 2>&1 | grep -q "gcc version" && echo "gcc"),gcc)
$(warning warning: gcc/g++ support is experimental. For normal testing, clang is recommended)
# no -Werror, allow warning for gcc now
COMMON_FLAGS += -Wno-missing-field-initializers
endif # is clang / gcc
$(info CC version: $(shell $(CC) --version))
$(info CXX version: $(shell $(CXX) --version))

View file

@ -64,9 +64,9 @@ extern "C" {
void *cliGetValuePointer(const clivalue_t *value);
const clivalue_t valueTable[] = {
{ "array_unit_test", VAR_INT8 | MODE_ARRAY | MASTER_VALUE, .config.array.length = 3, PG_RESERVED_FOR_TESTING_1, 0 },
{ "str_unit_test", VAR_UINT8 | MODE_STRING | MASTER_VALUE, .config.string = { 0, 16, 0 }, PG_RESERVED_FOR_TESTING_1, 0 },
{ "wos_unit_test", VAR_UINT8 | MODE_STRING | MASTER_VALUE, .config.string = { 0, 16, STRING_FLAGS_WRITEONCE }, PG_RESERVED_FOR_TESTING_1, 0 },
{ .name = "array_unit_test", .type = VAR_INT8 | MODE_ARRAY | MASTER_VALUE, .config = { .array = { .length = 3}}, .pgn = PG_RESERVED_FOR_TESTING_1, .offset = 0 },
{ .name = "str_unit_test", .type = VAR_UINT8 | MODE_STRING | MASTER_VALUE, .config = { .string = { 0, 16, 0 }}, .pgn = PG_RESERVED_FOR_TESTING_1, .offset = 0 },
{ .name = "wos_unit_test", .type = VAR_UINT8 | MODE_STRING | MASTER_VALUE, .config = { .string = { 0, 16, STRING_FLAGS_WRITEONCE }}, .pgn = PG_RESERVED_FOR_TESTING_1, .offset = 0 },
};
const uint16_t valueTableEntryCount = ARRAYLEN(valueTable);
const lookupTableEntry_t lookupTables[] = {};
@ -103,6 +103,8 @@ extern "C" {
#include "unittest_macros.h"
#include "gtest/gtest.h"
const bool PRINT_TEST_DATA = false;
TEST(CLIUnittest, TestCliSetArray)
{
char *str = (char *)"array_unit_test = 123, -3 , 1";
@ -112,14 +114,15 @@ TEST(CLIUnittest, TestCliSetArray)
EXPECT_LT(index, valueTableEntryCount);
const clivalue_t val = valueTable[index];
printf("\n===============================\n");
int8_t *data = (int8_t *)cliGetValuePointer(&val);
for(int i=0; i < val.config.array.length; i++){
if (PRINT_TEST_DATA) {
printf("\n===============================\n");
for(int i = 0; i < val.config.array.length; i++){
printf("data[%d] = %d\n", i, data[i]);
}
printf("\n===============================\n");
}
EXPECT_EQ(123, data[0]);
EXPECT_EQ( -3, data[1]);
@ -135,14 +138,15 @@ TEST(CLIUnittest, TestCliSetStringNoFlags)
EXPECT_LT(index, valueTableEntryCount);
const clivalue_t val = valueTable[index];
printf("\n===============================\n");
uint8_t *data = (uint8_t *)cliGetValuePointer(&val);
if (PRINT_TEST_DATA) {
printf("\n===============================\n");
for(int i = 0; i < val.config.string.maxlength && data[i] != 0; i++){
printf("data[%d] = %d (%c)\n", i, data[i], data[i]);
}
printf("\n===============================\n");
}
EXPECT_EQ('S', data[0]);
EXPECT_EQ('A', data[1]);
@ -164,13 +168,14 @@ TEST(CLIUnittest, TestCliSetStringWriteOnce)
const clivalue_t val = valueTable[index];
printf("\n===============================\n");
uint8_t *data = (uint8_t *)cliGetValuePointer(&val);
if (PRINT_TEST_DATA) {
printf("\n===============================\n");
for(int i = 0; i < val.config.string.maxlength && data[i] != 0; i++){
printf("data[%d] = %d (%c)\n", i, data[i], data[i]);
}
printf("\n===============================\n");
}
EXPECT_EQ('S', data[0]);
EXPECT_EQ('A', data[1]);
EXPECT_EQ('M', data[2]);
@ -198,8 +203,6 @@ TEST(CLIUnittest, TestCliSetStringWriteOnce)
EXPECT_EQ('L', data[4]);
EXPECT_EQ('E', data[5]);
EXPECT_EQ(0, data[6]);
printf("\n");
}
// STUBS

View file

@ -76,7 +76,7 @@ extern "C" {
TEST(LedStripTest, parseLedStripConfig)
{
// given
memset(&ledStripStatusModeConfigMutable()->ledConfigs, 0, LED_STRIP_MAX_LENGTH);
memset(&ledStripStatusModeConfigMutable()->ledConfigs, 0, sizeof(ledStripStatusModeConfigMutable()->ledConfigs));
// and
static const ledConfig_t expectedLedStripConfig[WS2811_LED_STRIP_LENGTH] = {
@ -197,7 +197,7 @@ TEST(LedStripTest, parseLedStripConfig)
TEST(LedStripTest, smallestGridWithCenter)
{
// given
memset(&ledStripStatusModeConfigMutable()->ledConfigs, 0, LED_STRIP_MAX_LENGTH);
memset(&ledStripStatusModeConfigMutable()->ledConfigs, 0, sizeof(ledStripStatusModeConfigMutable()->ledConfigs));
// and
static const ledConfig_t testLedConfigs[] = {
@ -225,7 +225,7 @@ TEST(LedStripTest, smallestGridWithCenter)
TEST(LedStripTest, smallestGrid)
{
// given
memset(&ledStripStatusModeConfigMutable()->ledConfigs, 0, LED_STRIP_MAX_LENGTH);
memset(&ledStripStatusModeConfigMutable()->ledConfigs, 0, sizeof(ledStripStatusModeConfigMutable()->ledConfigs));
// and
static const ledConfig_t testLedConfigs[] = {

View file

@ -19,4 +19,4 @@ SECTIONS {
PROVIDE_HIDDEN (___pg_resetdata_end = . );
}
}
INSERT AFTER .text;
INSERT AFTER .rodata;

View file

@ -35,10 +35,10 @@ extern "C" {
PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 1);
PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
.dev = {.motorPwmRate = 400},
.minthrottle = 1150,
.maxthrottle = 1850,
.mincommand = 1000,
.dev = {.motorPwmRate = 400}
);
}

View file

@ -260,14 +260,11 @@ extern "C" {
class RcControlsAdjustmentsTest : public ::testing::Test {
protected:
controlRateConfig_t controlRateConfig = {
.rcRates[FD_ROLL] = 90,
.rcRates[FD_PITCH] = 90,
.rcExpo[FD_ROLL] = 0,
.rcExpo[FD_PITCH] = 0,
.thrMid8 = 0,
.thrExpo8 = 0,
.rcRates = {[FD_ROLL] = 90, [FD_PITCH] = 90},
.rcExpo = {[FD_ROLL] = 0, [FD_PITCH] = 0, [FD_YAW] = 0},
.rates = {0, 0, 0},
.rcExpo[FD_YAW] = 0,
};
channelRange_t fullRange = {
@ -362,14 +359,11 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
{
// given
controlRateConfig_t controlRateConfig = {
.rcRates[FD_ROLL] = 90,
.rcRates[FD_PITCH] = 90,
.rcExpo[FD_ROLL] = 0,
.rcExpo[FD_PITCH] = 0,
.thrMid8 = 0,
.thrExpo8 = 0,
.rcRates = {[FD_ROLL] = 90, [FD_PITCH] = 90},
.rcExpo = {[FD_ROLL] = 0, [FD_PITCH] = 0, [FD_YAW] = 0},
.rates = {0,0,0},
.rcExpo[FD_YAW] = 0,
};
// and

View file

@ -84,8 +84,8 @@ typedef struct serialPortStub_s {
static serialPort_t serialTestInstance;
static serialPortConfig_t serialTestInstanceConfig = {
.functionMask = 0,
.identifier = SERIAL_PORT_DUMMY_IDENTIFIER,
.functionMask = 0
};
static serialReceiveCallbackPtr stub_serialRxCallback;

View file

@ -61,6 +61,9 @@ extern "C" {
#include "unittest_macros.h"
#include "gtest/gtest.h"
// set to dump generted sequences during test
const bool PRINT_FHSS_SEQUENCES = false;
//make clean test_rx_spi_expresslrs_unittest
TEST(RxSpiExpressLrsUnitTest, TestCrc14)
{
@ -176,13 +179,17 @@ TEST(RxSpiExpressLrsUnitTest, TestFHSSTable)
};
fhssGenSequence(UID, ISM2400);
if (PRINT_FHSS_SEQUENCES) {
printFhssSequence(fhssSequence);
}
for (int i = 0; i < ELRS_NR_SEQUENCE_ENTRIES; i++) {
EXPECT_EQ(expectedSequence[0][i], fhssSequence[i]);
}
fhssGenSequence(UID, FCC915);
if (PRINT_FHSS_SEQUENCES) {
printFhssSequence(fhssSequence);
}
for (int i = 0; i < ELRS_NR_SEQUENCE_ENTRIES; i++) {
EXPECT_EQ(expectedSequence[1][i], fhssSequence[i]);
}

View file

@ -85,7 +85,7 @@ extern "C" {
} dsmReceiver_t;
extern dsmReceiver_t dsmReceiver;
extern bool isError = false;
bool isError = false;
static const dsmReceiver_t empty = dsmReceiver_t();
static rxRuntimeState_t config = rxRuntimeState_t();

View file

@ -86,8 +86,8 @@ typedef struct serialPortStub_s {
static serialPort_t serialTestInstance;
static serialPortConfig_t serialTestInstanceConfig = {
.functionMask = 0,
.identifier = SERIAL_PORT_DUMMY_IDENTIFIER,
.functionMask = 0
};
static serialReceiveCallbackPtr stub_serialRxCallback;

View file

@ -0,0 +1,119 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software under the terms of the GNU General
* Public License as published by the Free Software Foundation,
* either version 3 of the License, or (at your option) any later
* version.
*
* Betaflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
*
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public
* License along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "scheduler/scheduler.h"
#include "scheduler_stubs.h"
PG_REGISTER_WITH_RESET_TEMPLATE(schedulerConfig_t, schedulerConfig, PG_SCHEDULER_CONFIG, 0);
PG_RESET_TEMPLATE(schedulerConfig_t, schedulerConfig,
.rxRelaxDeterminism = 25,
.osdRelaxDeterminism = 25,
);
#define TEST_GYRO_SAMPLE_HZ 8000
void taskGyroSample(timeUs_t);
void taskFiltering(timeUs_t);
void taskMainPidLoop(timeUs_t);
void taskUpdateAccelerometer(timeUs_t);
void taskHandleSerial(timeUs_t);
void taskUpdateBatteryVoltage(timeUs_t);
bool rxUpdateCheck(timeUs_t, timeDelta_t);
void taskUpdateRxMain(timeUs_t);
void imuUpdateAttitude(timeUs_t);
void dispatchProcess(timeUs_t);
bool osdUpdateCheck(timeUs_t, timeDelta_t);
void osdUpdate(timeUs_t);
task_attribute_t task_attributes[TASK_COUNT] = {
[TASK_SYSTEM] = {
.taskName = "SYSTEM",
.taskFunc = taskSystemLoad,
.desiredPeriodUs = TASK_PERIOD_HZ(10),
.staticPriority = TASK_PRIORITY_MEDIUM_HIGH,
},
[TASK_GYRO] = {
.taskName = "GYRO",
.taskFunc = taskGyroSample,
.desiredPeriodUs = TASK_PERIOD_HZ(TEST_GYRO_SAMPLE_HZ),
.staticPriority = TASK_PRIORITY_REALTIME,
},
[TASK_FILTER] = {
.taskName = "FILTER",
.taskFunc = taskFiltering,
.desiredPeriodUs = TASK_PERIOD_HZ(4000),
.staticPriority = TASK_PRIORITY_REALTIME,
},
[TASK_PID] = {
.taskName = "PID",
.taskFunc = taskMainPidLoop,
.desiredPeriodUs = TASK_PERIOD_HZ(4000),
.staticPriority = TASK_PRIORITY_REALTIME,
},
[TASK_ACCEL] = {
.taskName = "ACCEL",
.taskFunc = taskUpdateAccelerometer,
.desiredPeriodUs = TASK_PERIOD_HZ(1000),
.staticPriority = TASK_PRIORITY_MEDIUM,
},
[TASK_ATTITUDE] = {
.taskName = "ATTITUDE",
.taskFunc = imuUpdateAttitude,
.desiredPeriodUs = TASK_PERIOD_HZ(100),
.staticPriority = TASK_PRIORITY_MEDIUM,
},
[TASK_RX] = {
.taskName = "RX",
.checkFunc = rxUpdateCheck,
.taskFunc = taskUpdateRxMain,
.desiredPeriodUs = TASK_PERIOD_HZ(50),
.staticPriority = TASK_PRIORITY_HIGH,
},
[TASK_SERIAL] = {
.taskName = "SERIAL",
.taskFunc = taskHandleSerial,
.desiredPeriodUs = TASK_PERIOD_HZ(100),
.staticPriority = TASK_PRIORITY_LOW,
},
[TASK_DISPATCH] = {
.taskName = "DISPATCH",
.taskFunc = dispatchProcess,
.desiredPeriodUs = TASK_PERIOD_HZ(1000),
.staticPriority = TASK_PRIORITY_HIGH,
},
[TASK_BATTERY_VOLTAGE] = {
.taskName = "BATTERY_VOLTAGE",
.taskFunc = taskUpdateBatteryVoltage,
.desiredPeriodUs = TASK_PERIOD_HZ(50),
.staticPriority = TASK_PRIORITY_MEDIUM,
},
[TASK_OSD] = {
.taskName = "OSD",
.checkFunc = osdUpdateCheck,
.taskFunc = osdUpdate,
.desiredPeriodUs = TASK_PERIOD_HZ(12),
.staticPriority = TASK_PRIORITY_LOW,
}
};

View file

@ -0,0 +1,26 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software under the terms of the GNU General
* Public License as published by the Free Software Foundation,
* either version 3 of the License, or (at your option) any later
* version.
*
* Betaflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
*
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public
* License along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "scheduler/scheduler.h"
extern task_attribute_t task_attributes[TASK_COUNT];

View file

@ -20,17 +20,8 @@
extern "C" {
#include "drivers/accgyro/accgyro.h"
#include "platform.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/scheduler.h"
#include "scheduler/scheduler.h"
PG_REGISTER_WITH_RESET_TEMPLATE(schedulerConfig_t, schedulerConfig, PG_SCHEDULER_CONFIG, 0);
PG_RESET_TEMPLATE(schedulerConfig_t, schedulerConfig,
.rxRelaxDeterminism = 25,
.osdRelaxDeterminism = 25,
);
#include "scheduler_stubs.h"
}
#include "unittest_macros.h"
@ -76,7 +67,7 @@ extern "C" {
uint32_t millis(void) { return simulatedTime/1000; } // Note simplistic mapping suitable only for short unit tests
int32_t clockCyclesToMicros(int32_t x) { return x/10;}
int32_t clockCyclesTo10thMicros(int32_t x) { return x;}
int32_t clockCyclesTo100thMicros(int32_t x) { return x;}
int32_t clockCyclesTo100thMicros(int32_t x) { return x * 10;}
uint32_t clockMicrosToCycles(uint32_t x) { return x*10;}
uint32_t getCycleCounter(void) {return simulatedTime * 10;}
@ -120,77 +111,6 @@ extern "C" {
extern task_t *queueFirst(void);
extern task_t *queueNext(void);
task_attribute_t task_attributes[TASK_COUNT] = {
[TASK_SYSTEM] = {
.taskName = "SYSTEM",
.taskFunc = taskSystemLoad,
.desiredPeriodUs = TASK_PERIOD_HZ(10),
.staticPriority = TASK_PRIORITY_MEDIUM_HIGH,
},
[TASK_GYRO] = {
.taskName = "GYRO",
.taskFunc = taskGyroSample,
.desiredPeriodUs = TASK_PERIOD_HZ(TEST_GYRO_SAMPLE_HZ),
.staticPriority = TASK_PRIORITY_REALTIME,
},
[TASK_FILTER] = {
.taskName = "FILTER",
.taskFunc = taskFiltering,
.desiredPeriodUs = TASK_PERIOD_HZ(4000),
.staticPriority = TASK_PRIORITY_REALTIME,
},
[TASK_PID] = {
.taskName = "PID",
.taskFunc = taskMainPidLoop,
.desiredPeriodUs = TASK_PERIOD_HZ(4000),
.staticPriority = TASK_PRIORITY_REALTIME,
},
[TASK_ACCEL] = {
.taskName = "ACCEL",
.taskFunc = taskUpdateAccelerometer,
.desiredPeriodUs = TASK_PERIOD_HZ(1000),
.staticPriority = TASK_PRIORITY_MEDIUM,
},
[TASK_ATTITUDE] = {
.taskName = "ATTITUDE",
.taskFunc = imuUpdateAttitude,
.desiredPeriodUs = TASK_PERIOD_HZ(100),
.staticPriority = TASK_PRIORITY_MEDIUM,
},
[TASK_RX] = {
.taskName = "RX",
.checkFunc = rxUpdateCheck,
.taskFunc = taskUpdateRxMain,
.desiredPeriodUs = TASK_PERIOD_HZ(50),
.staticPriority = TASK_PRIORITY_HIGH,
},
[TASK_SERIAL] = {
.taskName = "SERIAL",
.taskFunc = taskHandleSerial,
.desiredPeriodUs = TASK_PERIOD_HZ(100),
.staticPriority = TASK_PRIORITY_LOW,
},
[TASK_DISPATCH] = {
.taskName = "DISPATCH",
.taskFunc = dispatchProcess,
.desiredPeriodUs = TASK_PERIOD_HZ(1000),
.staticPriority = TASK_PRIORITY_HIGH,
},
[TASK_BATTERY_VOLTAGE] = {
.taskName = "BATTERY_VOLTAGE",
.taskFunc = taskUpdateBatteryVoltage,
.desiredPeriodUs = TASK_PERIOD_HZ(50),
.staticPriority = TASK_PRIORITY_MEDIUM,
},
[TASK_OSD] = {
.taskName = "OSD",
.checkFunc = osdUpdateCheck,
.taskFunc = osdUpdate,
.desiredPeriodUs = TASK_PERIOD_HZ(12),
.staticPriority = TASK_PRIORITY_LOW,
}
};
task_t tasks[TASK_COUNT];
task_t *getTask(unsigned taskId)

View file

@ -101,6 +101,16 @@ uint16_t getBatteryAverageCellVoltage(void)
return testBatteryVoltage / testBatteryCellCount;
}
uint16_t getBatteryVoltage(void)
{
return testBatteryVoltage;
}
uint8_t getBatteryCellCount(void)
{
return testBatteryCellCount;
}
int32_t getMAhDrawn(void)
{
return 0;
@ -120,7 +130,7 @@ bool sensors(sensors_e sensor)
{
return (definedSensors & sensor) != 0;
}
}
} /* extern "C" */
#define SERIAL_BUFFER_SIZE 256
@ -130,25 +140,14 @@ typedef struct serialPortStub_s {
int end = 0;
} serialPortStub_t;
uint16_t getBatteryVoltage(void)
{
return testBatteryVoltage;
}
uint8_t getBatteryCellCount(void)
{
return testBatteryCellCount;
}
static serialPortStub_t serialWriteStub;
static serialPortStub_t serialReadStub;
#define SERIAL_PORT_DUMMY_IDENTIFIER (serialPortIdentifier_e)0x12
serialPort_t serialTestInstance;
serialPortConfig_t serialTestInstanceConfig = {
.functionMask = 0,
.identifier = SERIAL_PORT_DUMMY_IDENTIFIER,
.functionMask = 0
};
static serialPortConfig_t *findSerialPortConfig_stub_retval;
@ -273,8 +272,8 @@ uint8_t serialRead(serialPort_t *instance)
void serialTestResetBuffers()
{
memset(&serialReadStub, 0, sizeof(serialReadStub));
memset(&serialWriteStub, 0, sizeof(serialWriteStub));
serialReadStub = { {0} };
serialWriteStub = { {0} };
}
void setTestSensors()