mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 21:35:44 +03:00
Add back and refactor some unit tests.
Re-enabled: - BMP280 - MS5166 - Maths test cases - Serial IO Refactored: - Scheduler Tried to decouple the test from the actual tasks (in fc_tashs.h/c) in the majority of logical tests.
This commit is contained in:
parent
99b11eb1b1
commit
ffeddc958c
10 changed files with 238 additions and 260 deletions
|
@ -23,7 +23,6 @@
|
|||
cfTask_t *unittest_scheduler_selectedTask;
|
||||
uint8_t unittest_scheduler_selectedTaskDynamicPriority;
|
||||
uint16_t unittest_scheduler_waitingTasks;
|
||||
uint32_t unittest_scheduler_timeToNextRealtimeTask;
|
||||
bool unittest_outsideRealtimeGuardInterval;
|
||||
|
||||
#define GET_SCHEDULER_LOCALS() \
|
||||
|
@ -31,7 +30,6 @@ bool unittest_outsideRealtimeGuardInterval;
|
|||
unittest_scheduler_selectedTask = selectedTask; \
|
||||
unittest_scheduler_selectedTaskDynamicPriority = selectedTaskDynamicPriority; \
|
||||
unittest_scheduler_waitingTasks = waitingTasks; \
|
||||
unittest_scheduler_timeToNextRealtimeTask = timeToNextRealtimeTask; \
|
||||
unittest_outsideRealtimeGuardInterval = outsideRealtimeGuardInterval; \
|
||||
}
|
||||
|
||||
|
|
|
@ -23,10 +23,13 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
#include "config/config_unittest.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/time.h"
|
||||
#include "common/utils.h"
|
||||
|
@ -49,10 +52,11 @@ uint16_t averageSystemLoadPercent = 0;
|
|||
|
||||
|
||||
static int taskQueuePos = 0;
|
||||
static int taskQueueSize = 0;
|
||||
STATIC_UNIT_TESTED int taskQueueSize = 0;
|
||||
|
||||
// No need for a linked list for the queue, since items are only inserted at startup
|
||||
|
||||
static cfTask_t* taskQueueArray[TASK_COUNT + 1]; // extra item for NULL pointer at end of queue
|
||||
STATIC_UNIT_TESTED cfTask_t* taskQueueArray[TASK_COUNT + 1]; // extra item for NULL pointer at end of queue
|
||||
|
||||
void queueClear(void)
|
||||
{
|
||||
|
@ -329,4 +333,6 @@ void scheduler(void)
|
|||
DEBUG_SET(DEBUG_SCHEDULER, 2, micros() - currentTimeUs);
|
||||
#endif
|
||||
}
|
||||
|
||||
GET_SCHEDULER_LOCALS();
|
||||
}
|
||||
|
|
|
@ -29,16 +29,16 @@ altitude_hold_unittest_SRC := \
|
|||
|
||||
|
||||
baro_bmp085_unittest_SRC := \
|
||||
$(USER_DIR)/drivers/barometer_bmp085.c \
|
||||
$(USER_DIR)/drivers/barometer/barometer_bmp085.c \
|
||||
$(USER_DIR)/drivers/io.c
|
||||
|
||||
|
||||
baro_bmp280_unittest_SRC := \
|
||||
$(USER_DIR)/drivers/barometer_bmp280.c
|
||||
$(USER_DIR)/drivers/barometer/barometer_bmp280.c
|
||||
|
||||
|
||||
baro_ms5611_unittest_SRC := \
|
||||
$(USER_DIR)/drivers/barometer_ms5611.c
|
||||
$(USER_DIR)/drivers/barometer/barometer_ms5611.c
|
||||
|
||||
|
||||
battery_unittest_SRC := \
|
||||
|
@ -52,6 +52,7 @@ blackbox_encoding_unittest_SRC := \
|
|||
$(USER_DIR)/common/printf.c \
|
||||
$(USER_DIR)/common/typeconversion.c
|
||||
|
||||
|
||||
cms_unittest_SRC := \
|
||||
$(USER_DIR)/cms/cms.c \
|
||||
$(USER_DIR)/common/typeconversion.c \
|
||||
|
@ -87,7 +88,8 @@ gps_conversion_unittest_SRC := \
|
|||
|
||||
|
||||
io_serial_unittest_SRC := \
|
||||
$(USER_DIR)/io/serial.c
|
||||
$(USER_DIR)/io/serial.c \
|
||||
$(USER_DIR)/drivers/serial_pinconfig.c
|
||||
|
||||
|
||||
ledstrip_unittest_SRC := \
|
||||
|
@ -127,14 +129,8 @@ rx_rx_unittest_SRC := \
|
|||
$(USER_DIR)/config/feature.c
|
||||
|
||||
|
||||
sensor_gyro_unittest_SRC := \
|
||||
$(USER_DIR)/sensors/gyro.c \
|
||||
$(USER_DIR)/sensors/boardalignment.c \
|
||||
$(USER_DIR)/build/debug.c \
|
||||
$(USER_DIR)/common/filter.c \
|
||||
$(USER_DIR)/common/maths.c \
|
||||
$(USER_DIR)/drivers/accgyro_fake.c \
|
||||
$(USER_DIR)/drivers/gyro_sync.c
|
||||
scheduler_unittest_SRC := \
|
||||
$(USER_DIR)/scheduler/scheduler.c
|
||||
|
||||
|
||||
telemetry_crsf_unittest_SRC := \
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
extern "C" {
|
||||
|
||||
void bmp280_calculate(int32_t *pressure, int32_t *temperature);
|
||||
|
||||
extern uint32_t bmp280_up;
|
||||
extern uint32_t bmp280_ut;
|
||||
|
||||
|
@ -48,7 +49,6 @@ typedef struct bmp280_calib_param_s {
|
|||
|
||||
TEST(baroBmp280Test, TestBmp280Calculate)
|
||||
{
|
||||
|
||||
// given
|
||||
int32_t pressure, temperature;
|
||||
bmp280_up = 415148; // Digital pressure value
|
||||
|
@ -74,12 +74,10 @@ TEST(baroBmp280Test, TestBmp280Calculate)
|
|||
// then
|
||||
EXPECT_EQ(100653, pressure); // 100653 Pa
|
||||
EXPECT_EQ(2508, temperature); // 25.08 degC
|
||||
|
||||
}
|
||||
|
||||
TEST(baroBmp280Test, TestBmp280CalculateHighP)
|
||||
{
|
||||
|
||||
// given
|
||||
int32_t pressure, temperature;
|
||||
bmp280_up = 215148; // Digital pressure value
|
||||
|
@ -105,12 +103,10 @@ TEST(baroBmp280Test, TestBmp280CalculateHighP)
|
|||
// then
|
||||
EXPECT_EQ(135382, pressure); // 135385 Pa
|
||||
EXPECT_EQ(2508, temperature); // 25.08 degC
|
||||
|
||||
}
|
||||
|
||||
TEST(baroBmp280Test, TestBmp280CalculateZeroP)
|
||||
{
|
||||
|
||||
// given
|
||||
int32_t pressure, temperature;
|
||||
bmp280_up = 415148; // Digital pressure value
|
||||
|
@ -136,7 +132,6 @@ TEST(baroBmp280Test, TestBmp280CalculateZeroP)
|
|||
// then
|
||||
EXPECT_EQ(0, pressure); // P1=0 trips pressure to 0 Pa, avoiding division by zero
|
||||
EXPECT_EQ(2508, temperature); // 25.08 degC
|
||||
|
||||
}
|
||||
|
||||
// STUBS
|
||||
|
@ -144,11 +139,13 @@ TEST(baroBmp280Test, TestBmp280CalculateZeroP)
|
|||
extern "C" {
|
||||
|
||||
void delay(uint32_t) {}
|
||||
|
||||
bool i2cWrite(uint8_t, uint8_t, uint8_t) {
|
||||
return 1;
|
||||
return true;
|
||||
}
|
||||
|
||||
bool i2cRead(uint8_t, uint8_t, uint8_t, uint8_t) {
|
||||
return 1;
|
||||
return true;
|
||||
}
|
||||
|
||||
}
|
|
@ -34,7 +34,6 @@ extern uint32_t ms5611_ut;
|
|||
|
||||
TEST(baroMS5611Test, TestValidMs5611Crc)
|
||||
{
|
||||
|
||||
// given
|
||||
uint16_t ms5611_prom[] = {0x3132,0x3334,0x3536,0x3738,0x3940,0x4142,0x4344,0x450B};
|
||||
|
||||
|
@ -43,12 +42,10 @@ TEST(baroMS5611Test, TestValidMs5611Crc)
|
|||
|
||||
// then
|
||||
EXPECT_EQ(0, result);
|
||||
|
||||
}
|
||||
|
||||
TEST(baroMS5611Test, TestInvalidMs5611Crc)
|
||||
{
|
||||
|
||||
// given
|
||||
uint16_t ms5611_prom[] = {0x3132,0x3334,0x3536,0x3738,0x3940,0x4142,0x4344,0x4500};
|
||||
|
||||
|
@ -57,12 +54,10 @@ TEST(baroMS5611Test, TestInvalidMs5611Crc)
|
|||
|
||||
// then
|
||||
EXPECT_EQ(-1, result);
|
||||
|
||||
}
|
||||
|
||||
TEST(baroMS5611Test, TestMs5611AllZeroProm)
|
||||
{
|
||||
|
||||
// given
|
||||
uint16_t ms5611_prom[] = {0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000};
|
||||
|
||||
|
@ -71,12 +66,10 @@ TEST(baroMS5611Test, TestMs5611AllZeroProm)
|
|||
|
||||
// then
|
||||
EXPECT_EQ(-1, result);
|
||||
|
||||
}
|
||||
|
||||
TEST(baroMS5611Test, TestMs5611AllOnesProm)
|
||||
{
|
||||
|
||||
// given
|
||||
uint16_t ms5611_prom[] = {0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF};
|
||||
|
||||
|
@ -85,12 +78,10 @@ TEST(baroMS5611Test, TestMs5611AllOnesProm)
|
|||
|
||||
// then
|
||||
EXPECT_EQ(-1, result);
|
||||
|
||||
}
|
||||
|
||||
TEST(baroMS5611Test, TestMs5611CalculatePressureGT20Deg)
|
||||
{
|
||||
|
||||
// given
|
||||
int32_t pressure, temperature;
|
||||
uint16_t ms5611_c_test[] = {0x0000, 40127, 36924, 23317, 23282, 33464, 28312, 0x0000}; // calibration data from MS5611 datasheet
|
||||
|
@ -105,12 +96,10 @@ TEST(baroMS5611Test, TestMs5611CalculatePressureGT20Deg)
|
|||
// then
|
||||
EXPECT_EQ(2007, temperature); // 20.07 deg C
|
||||
EXPECT_EQ(100009, pressure); // 1000.09 mbar
|
||||
|
||||
}
|
||||
|
||||
TEST(baroMS5611Test, TestMs5611CalculatePressureLT20Deg)
|
||||
{
|
||||
|
||||
// given
|
||||
int32_t pressure, temperature;
|
||||
uint16_t ms5611_c_test[] = {0x0000, 40127, 36924, 23317, 23282, 33464, 28312, 0x0000}; // calibration data from MS5611 datasheet
|
||||
|
@ -125,12 +114,10 @@ TEST(baroMS5611Test, TestMs5611CalculatePressureLT20Deg)
|
|||
// then
|
||||
EXPECT_EQ(205, temperature); // 2.05 deg C
|
||||
EXPECT_EQ(96512, pressure); // 965.12 mbar
|
||||
|
||||
}
|
||||
|
||||
TEST(baroMS5611Test, TestMs5611CalculatePressureLTMinus15Deg)
|
||||
{
|
||||
|
||||
// given
|
||||
int32_t pressure, temperature;
|
||||
uint16_t ms5611_c_test[] = {0x0000, 40127, 36924, 23317, 23282, 33464, 28312, 0x0000}; // calibration data from MS5611 datasheet
|
||||
|
@ -145,7 +132,6 @@ TEST(baroMS5611Test, TestMs5611CalculatePressureLTMinus15Deg)
|
|||
// then
|
||||
EXPECT_EQ(-2710, temperature); // -27.10 deg C
|
||||
EXPECT_EQ(90613, pressure); // 906.13 mbar
|
||||
|
||||
}
|
||||
|
||||
// STUBS
|
||||
|
@ -154,11 +140,13 @@ extern "C" {
|
|||
|
||||
void delay(uint32_t) {}
|
||||
void delayMicroseconds(uint32_t) {}
|
||||
|
||||
bool i2cWrite(uint8_t, uint8_t, uint8_t) {
|
||||
return 1;
|
||||
return true;
|
||||
}
|
||||
|
||||
bool i2cRead(uint8_t, uint8_t, uint8_t, uint8_t) {
|
||||
return 1;
|
||||
return true;
|
||||
}
|
||||
|
||||
}
|
|
@ -24,28 +24,23 @@ extern "C" {
|
|||
#include "platform.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_softserial.h"
|
||||
#include "drivers/serial_uart.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
void serialInit(serialConfig_t *initialSerialConfig);
|
||||
|
||||
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
//uint32_t testFeatureMask = 0;
|
||||
uint8_t cliMode = 0;
|
||||
|
||||
TEST(IoSerialTest, TestFindPortConfig)
|
||||
{
|
||||
// given
|
||||
serialConfig_t serialConfig;
|
||||
memset(&serialConfig, 0, sizeof(serialConfig));
|
||||
serialInit(false, SERIAL_PORT_NONE);
|
||||
|
||||
// when
|
||||
serialInit(&serialConfig);
|
||||
|
||||
// and
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP);
|
||||
|
||||
// then
|
||||
|
@ -54,20 +49,26 @@ TEST(IoSerialTest, TestFindPortConfig)
|
|||
|
||||
|
||||
// STUBS
|
||||
|
||||
extern "C" {
|
||||
//
|
||||
//bool feature(uint32_t mask) {
|
||||
// return (mask & testFeatureMask);
|
||||
//}s
|
||||
|
||||
void delay(uint32_t) {}
|
||||
void cliEnter(serialPort_t *) {}
|
||||
void cliProcess(void) {}
|
||||
bool isSerialTransmitBufferEmpty(serialPort_t *) {
|
||||
return true;
|
||||
}
|
||||
void mspProcess(void) {}
|
||||
|
||||
bool isSerialTransmitBufferEmpty(const serialPort_t *) { return true; }
|
||||
|
||||
void systemResetToBootloader(void) {}
|
||||
|
||||
bool telemetryCheckRxPortShared(const serialPortConfig_t *) { return false; }
|
||||
|
||||
uint32_t serialRxBytesWaiting(const serialPort_t *) { return 0; }
|
||||
uint8_t serialRead(serialPort_t *) { return 0; }
|
||||
void serialWrite(serialPort_t *, uint8_t) {}
|
||||
|
||||
serialPort_t *usbVcpOpen(void) { return NULL; }
|
||||
|
||||
serialPort_t *uartOpen(UARTDevice, serialReceiveCallbackPtr, uint32_t, portMode_t, portOptions_t) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
serialPort_t *openSoftSerial(softSerialPortIndex_e, serialReceiveCallbackPtr, uint32_t, portMode_t, portOptions_t) {
|
||||
return NULL;
|
||||
}
|
||||
}
|
|
@ -195,14 +195,13 @@ TEST(MathsUnittest, TestApplyDeadband)
|
|||
EXPECT_EQ(applyDeadband(-11, 10), -1);
|
||||
}
|
||||
|
||||
void expectVectorsAreEqual(struct fp_vector *a, struct fp_vector *b)
|
||||
void expectVectorsAreEqual(struct fp_vector *a, struct fp_vector *b, float absTol)
|
||||
{
|
||||
EXPECT_FLOAT_EQ(a->X, b->X);
|
||||
EXPECT_FLOAT_EQ(a->Y, b->Y);
|
||||
EXPECT_FLOAT_EQ(a->Z, b->Z);
|
||||
EXPECT_NEAR(a->X, b->X, absTol);
|
||||
EXPECT_NEAR(a->Y, b->Y, absTol);
|
||||
EXPECT_NEAR(a->Z, b->Z, absTol);
|
||||
}
|
||||
|
||||
/*
|
||||
TEST(MathsUnittest, TestRotateVectorWithNoAngle)
|
||||
{
|
||||
fp_vector vector = {1.0f, 0.0f, 0.0f};
|
||||
|
@ -211,7 +210,7 @@ TEST(MathsUnittest, TestRotateVectorWithNoAngle)
|
|||
rotateV(&vector, &euler_angles);
|
||||
fp_vector expected_result = {1.0f, 0.0f, 0.0f};
|
||||
|
||||
expectVectorsAreEqual(&vector, &expected_result);
|
||||
expectVectorsAreEqual(&vector, &expected_result, 1e-5);
|
||||
}
|
||||
|
||||
TEST(MathsUnittest, TestRotateVectorAroundAxis)
|
||||
|
@ -223,11 +222,10 @@ TEST(MathsUnittest, TestRotateVectorAroundAxis)
|
|||
rotateV(&vector, &euler_angles);
|
||||
fp_vector expected_result = {1.0f, 0.0f, 0.0f};
|
||||
|
||||
expectVectorsAreEqual(&vector, &expected_result);
|
||||
expectVectorsAreEqual(&vector, &expected_result, 1e-5);
|
||||
}
|
||||
*/
|
||||
|
||||
#if defined(FAST_MATH) || defined(VERY_FAST_MATH)
|
||||
/*
|
||||
TEST(MathsUnittest, TestFastTrigonometrySinCos)
|
||||
{
|
||||
double sinError = 0;
|
||||
|
@ -246,9 +244,8 @@ TEST(MathsUnittest, TestFastTrigonometrySinCos)
|
|||
cosError = MAX(cosError, fabs(approxResult - libmResult));
|
||||
}
|
||||
printf("cos_approx maximum absolute error = %e\n", cosError);
|
||||
EXPECT_LE(cosError, 3e-6);
|
||||
EXPECT_LE(cosError, 3.5e-6);
|
||||
}
|
||||
*/
|
||||
|
||||
TEST(MathsUnittest, TestFastTrigonometryATan2)
|
||||
{
|
||||
|
|
|
@ -85,6 +85,11 @@ typedef struct
|
|||
void* test;
|
||||
} USART_TypeDef;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
void *test;
|
||||
} I2C_TypeDef;
|
||||
|
||||
#define WS2811_DMA_TC_FLAG (void *)1
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER 0
|
||||
|
||||
|
|
|
@ -24,80 +24,117 @@ extern "C" {
|
|||
|
||||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
enum {
|
||||
systemTime = 10,
|
||||
pidLoopCheckerTime = 650,
|
||||
updateAccelerometerTime = 192,
|
||||
handleSerialTime = 30,
|
||||
updateBeeperTime = 1,
|
||||
updateBatteryTime = 1,
|
||||
updateRxCheckTime = 34,
|
||||
updateRxMainTime = 10,
|
||||
processGPSTime = 10,
|
||||
updateCompassTime = 195,
|
||||
updateBaroTime = 201,
|
||||
updateSonarTime = 10,
|
||||
calculateAltitudeTime = 154,
|
||||
updateDisplayTime = 10,
|
||||
telemetryTime = 10,
|
||||
ledStripTime = 10,
|
||||
transponderTime = 10
|
||||
};
|
||||
|
||||
const int TEST_PID_LOOP_TIME = 650;
|
||||
const int TEST_UPDATE_ACCEL_TIME = 192;
|
||||
const int TEST_HANDLE_SERIAL_TIME = 30;
|
||||
const int TEST_UPDATE_BATTERY_TIME = 1;
|
||||
const int TEST_UPDATE_RX_CHECK_TIME = 34;
|
||||
const int TEST_UPDATE_RX_MAIN_TIME = 1;
|
||||
const int TEST_IMU_UPDATE_TIME = 5;
|
||||
const int TEST_DISPATCH_TIME = 1;
|
||||
|
||||
#define TASK_COUNT_UNITTEST (TASK_BATTERY_VOLTAGE + 1)
|
||||
#define TASK_PERIOD_HZ(hz) (1000000 / (hz))
|
||||
|
||||
extern "C" {
|
||||
cfTask_t * unittest_scheduler_selectedTask;
|
||||
uint8_t unittest_scheduler_selectedTaskDynPrio;
|
||||
uint16_t unittest_scheduler_waitingTasks;
|
||||
uint32_t unittest_scheduler_timeToNextRealtimeTask;
|
||||
bool unittest_outsideRealtimeGuardInterval;
|
||||
|
||||
// set up micros() to simulate time
|
||||
uint32_t simulatedTime = 0;
|
||||
uint32_t micros(void) { return simulatedTime; }
|
||||
// set up tasks to take a simulated representative time to execute
|
||||
void taskMainPidLoopChecker(void) {simulatedTime+=pidLoopCheckerTime;}
|
||||
void taskUpdateAccelerometer(void) {simulatedTime+=updateAccelerometerTime;}
|
||||
void taskHandleSerial(void) {simulatedTime+=handleSerialTime;}
|
||||
void taskUpdateBeeper(void) {simulatedTime+=updateBeeperTime;}
|
||||
void taskUpdateBattery(void) {simulatedTime+=updateBatteryTime;}
|
||||
bool taskUpdateRxCheck(uint32_t currentDeltaTime) {UNUSED(currentDeltaTime);simulatedTime+=updateRxCheckTime;return false;}
|
||||
void taskUpdateRxMain(void) {simulatedTime+=updateRxMainTime;}
|
||||
void taskProcessGPS(void) {simulatedTime+=processGPSTime;}
|
||||
void taskUpdateCompass(void) {simulatedTime+=updateCompassTime;}
|
||||
void taskUpdateBaro(void) {simulatedTime+=updateBaroTime;}
|
||||
void taskUpdateSonar(void) {simulatedTime+=updateSonarTime;}
|
||||
void taskCalculateAltitude(void) {simulatedTime+=calculateAltitudeTime;}
|
||||
void taskUpdateDisplay(void) {simulatedTime+=updateDisplayTime;}
|
||||
void taskTelemetry(void) {simulatedTime+=telemetryTime;}
|
||||
void taskLedStrip(void) {simulatedTime+=ledStripTime;}
|
||||
void taskTransponder(void) {simulatedTime+=transponderTime;}
|
||||
|
||||
// set up tasks to take a simulated representative time to execute
|
||||
void taskMainPidLoop(timeUs_t) { simulatedTime += TEST_PID_LOOP_TIME; }
|
||||
void taskUpdateAccelerometer(timeUs_t) { simulatedTime += TEST_UPDATE_ACCEL_TIME; }
|
||||
void taskHandleSerial(timeUs_t) { simulatedTime += TEST_HANDLE_SERIAL_TIME; }
|
||||
void taskUpdateBatteryVoltage(timeUs_t) { simulatedTime += TEST_UPDATE_BATTERY_TIME; }
|
||||
bool rxUpdateCheck(timeUs_t, timeDelta_t) { simulatedTime += TEST_UPDATE_RX_CHECK_TIME; return false; }
|
||||
void taskUpdateRxMain(timeUs_t) { simulatedTime += TEST_UPDATE_RX_MAIN_TIME; }
|
||||
void imuUpdateAttitude(timeUs_t) { simulatedTime += TEST_IMU_UPDATE_TIME; }
|
||||
void dispatchProcess(timeUs_t) { simulatedTime += TEST_DISPATCH_TIME; }
|
||||
|
||||
extern int taskQueueSize;
|
||||
extern cfTask_t* taskQueueArray[];
|
||||
|
||||
extern void queueClear(void);
|
||||
extern int queueSize();
|
||||
extern bool queueContains(cfTask_t *task);
|
||||
extern bool queueAdd(cfTask_t *task);
|
||||
extern bool queueRemove(cfTask_t *task);
|
||||
extern cfTask_t *queueFirst(void);
|
||||
extern cfTask_t *queueNext(void);
|
||||
|
||||
cfTask_t cfTasks[TASK_COUNT] = {
|
||||
[TASK_SYSTEM] = {
|
||||
.taskName = "SYSTEM",
|
||||
.taskFunc = taskSystem,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(10),
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM_HIGH,
|
||||
},
|
||||
[TASK_GYROPID] = {
|
||||
.taskName = "PID",
|
||||
.subTaskName = "GYRO",
|
||||
.taskFunc = taskMainPidLoop,
|
||||
.desiredPeriod = 1000,
|
||||
.staticPriority = TASK_PRIORITY_REALTIME,
|
||||
},
|
||||
[TASK_ACCEL] = {
|
||||
.taskName = "ACCEL",
|
||||
.taskFunc = taskUpdateAccelerometer,
|
||||
.desiredPeriod = 10000,
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
[TASK_ATTITUDE] = {
|
||||
.taskName = "ATTITUDE",
|
||||
.taskFunc = imuUpdateAttitude,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(100),
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
[TASK_RX] = {
|
||||
.taskName = "RX",
|
||||
.checkFunc = rxUpdateCheck,
|
||||
.taskFunc = taskUpdateRxMain,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(50),
|
||||
.staticPriority = TASK_PRIORITY_HIGH,
|
||||
},
|
||||
[TASK_SERIAL] = {
|
||||
.taskName = "SERIAL",
|
||||
.taskFunc = taskHandleSerial,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(100),
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
[TASK_DISPATCH] = {
|
||||
.taskName = "DISPATCH",
|
||||
.taskFunc = dispatchProcess,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(1000),
|
||||
.staticPriority = TASK_PRIORITY_HIGH,
|
||||
},
|
||||
[TASK_BATTERY_VOLTAGE] = {
|
||||
.taskName = "BATTERY_VOLTAGE",
|
||||
.taskFunc = taskUpdateBatteryVoltage,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(50),
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
TEST(SchedulerUnittest, TestPriorites)
|
||||
{
|
||||
EXPECT_EQ(14, TASK_COUNT);
|
||||
// if any of these fail then task priorities have changed and ordering in TestQueue needs to be re-checked
|
||||
EXPECT_EQ(TASK_PRIORITY_HIGH, cfTasks[TASK_SYSTEM].staticPriority);
|
||||
EXPECT_EQ(20, TASK_COUNT);
|
||||
|
||||
EXPECT_EQ(TASK_PRIORITY_MEDIUM_HIGH, cfTasks[TASK_SYSTEM].staticPriority);
|
||||
EXPECT_EQ(TASK_PRIORITY_REALTIME, cfTasks[TASK_GYROPID].staticPriority);
|
||||
EXPECT_EQ(TASK_PRIORITY_MEDIUM, cfTasks[TASK_ACCEL].staticPriority);
|
||||
EXPECT_EQ(TASK_PRIORITY_LOW, cfTasks[TASK_SERIAL].staticPriority);
|
||||
EXPECT_EQ(TASK_PRIORITY_MEDIUM, cfTasks[TASK_BATTERY].staticPriority);
|
||||
EXPECT_EQ(TASK_PRIORITY_MEDIUM, cfTasks[TASK_BATTERY_VOLTAGE].staticPriority);
|
||||
}
|
||||
|
||||
TEST(SchedulerUnittest, TestQueueInit)
|
||||
{
|
||||
queueClear();
|
||||
EXPECT_EQ(0, queueSize());
|
||||
EXPECT_EQ(0, taskQueueSize);
|
||||
EXPECT_EQ(0, queueFirst());
|
||||
EXPECT_EQ(0, queueNext());
|
||||
for (int ii = 0; ii <= TASK_COUNT; ++ii) {
|
||||
|
@ -112,50 +149,50 @@ TEST(SchedulerUnittest, TestQueue)
|
|||
queueClear();
|
||||
taskQueueArray[TASK_COUNT + 1] = deadBeefPtr;
|
||||
|
||||
queueAdd(&cfTasks[TASK_SYSTEM]); // TASK_PRIORITY_HIGH
|
||||
EXPECT_EQ(1, queueSize());
|
||||
queueAdd(&cfTasks[TASK_SYSTEM]); // TASK_PRIORITY_MEDIUM_HIGH
|
||||
EXPECT_EQ(1, taskQueueSize);
|
||||
EXPECT_EQ(&cfTasks[TASK_SYSTEM], queueFirst());
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
|
||||
queueAdd(&cfTasks[TASK_GYROPID]); // TASK_PRIORITY_REALTIME
|
||||
EXPECT_EQ(2, queueSize());
|
||||
EXPECT_EQ(2, taskQueueSize);
|
||||
EXPECT_EQ(&cfTasks[TASK_GYROPID], queueFirst());
|
||||
EXPECT_EQ(&cfTasks[TASK_SYSTEM], queueNext());
|
||||
EXPECT_EQ(NULL, queueNext());
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
|
||||
queueAdd(&cfTasks[TASK_SERIAL]); // TASK_PRIORITY_LOW
|
||||
EXPECT_EQ(3, queueSize());
|
||||
EXPECT_EQ(3, taskQueueSize);
|
||||
EXPECT_EQ(&cfTasks[TASK_GYROPID], queueFirst());
|
||||
EXPECT_EQ(&cfTasks[TASK_SYSTEM], queueNext());
|
||||
EXPECT_EQ(&cfTasks[TASK_SERIAL], queueNext());
|
||||
EXPECT_EQ(NULL, queueNext());
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
|
||||
queueAdd(&cfTasks[TASK_BATTERY]); // TASK_PRIORITY_MEDIUM
|
||||
EXPECT_EQ(4, queueSize());
|
||||
queueAdd(&cfTasks[TASK_BATTERY_VOLTAGE]); // TASK_PRIORITY_MEDIUM
|
||||
EXPECT_EQ(4, taskQueueSize);
|
||||
EXPECT_EQ(&cfTasks[TASK_GYROPID], queueFirst());
|
||||
EXPECT_EQ(&cfTasks[TASK_SYSTEM], queueNext());
|
||||
EXPECT_EQ(&cfTasks[TASK_BATTERY], queueNext());
|
||||
EXPECT_EQ(&cfTasks[TASK_BATTERY_VOLTAGE], queueNext());
|
||||
EXPECT_EQ(&cfTasks[TASK_SERIAL], queueNext());
|
||||
EXPECT_EQ(NULL, queueNext());
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
|
||||
queueAdd(&cfTasks[TASK_RX]); // TASK_PRIORITY_HIGH
|
||||
EXPECT_EQ(5, queueSize());
|
||||
EXPECT_EQ(5, taskQueueSize);
|
||||
EXPECT_EQ(&cfTasks[TASK_GYROPID], queueFirst());
|
||||
EXPECT_EQ(&cfTasks[TASK_SYSTEM], queueNext());
|
||||
EXPECT_EQ(&cfTasks[TASK_RX], queueNext());
|
||||
EXPECT_EQ(&cfTasks[TASK_BATTERY], queueNext());
|
||||
EXPECT_EQ(&cfTasks[TASK_SYSTEM], queueNext());
|
||||
EXPECT_EQ(&cfTasks[TASK_BATTERY_VOLTAGE], queueNext());
|
||||
EXPECT_EQ(&cfTasks[TASK_SERIAL], queueNext());
|
||||
EXPECT_EQ(NULL, queueNext());
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
|
||||
queueRemove(&cfTasks[TASK_SYSTEM]); // TASK_PRIORITY_HIGH
|
||||
EXPECT_EQ(4, queueSize());
|
||||
EXPECT_EQ(4, taskQueueSize);
|
||||
EXPECT_EQ(&cfTasks[TASK_GYROPID], queueFirst());
|
||||
EXPECT_EQ(&cfTasks[TASK_RX], queueNext());
|
||||
EXPECT_EQ(&cfTasks[TASK_BATTERY], queueNext());
|
||||
EXPECT_EQ(&cfTasks[TASK_BATTERY_VOLTAGE], queueNext());
|
||||
EXPECT_EQ(&cfTasks[TASK_SERIAL], queueNext());
|
||||
EXPECT_EQ(NULL, queueNext());
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
|
@ -170,11 +207,12 @@ TEST(SchedulerUnittest, TestQueueAddAndRemove)
|
|||
for (int taskId = 0; taskId < TASK_COUNT; ++taskId) {
|
||||
const bool added = queueAdd(&cfTasks[taskId]);
|
||||
EXPECT_EQ(true, added);
|
||||
EXPECT_EQ(taskId + 1, queueSize());
|
||||
EXPECT_EQ(taskId + 1, taskQueueSize);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
}
|
||||
|
||||
// double check end of queue
|
||||
EXPECT_EQ(TASK_COUNT, queueSize());
|
||||
EXPECT_EQ(TASK_COUNT, taskQueueSize);
|
||||
EXPECT_NE(static_cast<cfTask_t*>(0), taskQueueArray[TASK_COUNT - 1]); // last item was indeed added to queue
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT]); // null pointer at end of queue is preserved
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]); // there hasn't been an out by one error
|
||||
|
@ -183,12 +221,13 @@ TEST(SchedulerUnittest, TestQueueAddAndRemove)
|
|||
for (int taskId = 0; taskId < TASK_COUNT; ++taskId) {
|
||||
const bool removed = queueRemove(&cfTasks[taskId]);
|
||||
EXPECT_EQ(true, removed);
|
||||
EXPECT_EQ(TASK_COUNT - taskId - 1, queueSize());
|
||||
EXPECT_EQ(TASK_COUNT - taskId - 1, taskQueueSize);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT - taskId]);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
}
|
||||
|
||||
// double check size and end of queue
|
||||
EXPECT_EQ(0, queueSize()); // queue is indeed empty
|
||||
EXPECT_EQ(0, taskQueueSize); // queue is indeed empty
|
||||
EXPECT_EQ(NULL, taskQueueArray[0]); // there is a null pointer at the end of the queueu
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]); // no accidental overwrites past end of queue
|
||||
}
|
||||
|
@ -197,72 +236,73 @@ TEST(SchedulerUnittest, TestQueueArray)
|
|||
{
|
||||
// test there are no "out by one" errors or buffer overruns when items are added and removed
|
||||
queueClear();
|
||||
taskQueueArray[TASK_COUNT + 1] = deadBeefPtr; // note, must set deadBeefPtr after queueClear
|
||||
taskQueueArray[TASK_COUNT_UNITTEST + 1] = deadBeefPtr; // note, must set deadBeefPtr after queueClear
|
||||
|
||||
for (int taskId = 0; taskId < TASK_COUNT - 1; ++taskId) {
|
||||
for (int taskId = 0; taskId < TASK_COUNT_UNITTEST - 1; ++taskId) {
|
||||
setTaskEnabled(static_cast<cfTaskId_e>(taskId), true);
|
||||
EXPECT_EQ(taskId + 1, queueSize());
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
EXPECT_EQ(taskId + 1, taskQueueSize);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
|
||||
}
|
||||
EXPECT_EQ(TASK_COUNT - 1, queueSize());
|
||||
EXPECT_NE(static_cast<cfTask_t*>(0), taskQueueArray[TASK_COUNT - 2]);
|
||||
const cfTask_t *lastTaskPrev = taskQueueArray[TASK_COUNT - 2];
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT]);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
|
||||
EXPECT_EQ(TASK_COUNT_UNITTEST - 1, taskQueueSize);
|
||||
EXPECT_NE(static_cast<cfTask_t*>(0), taskQueueArray[TASK_COUNT_UNITTEST - 2]);
|
||||
const cfTask_t *lastTaskPrev = taskQueueArray[TASK_COUNT_UNITTEST - 2];
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
|
||||
|
||||
setTaskEnabled(TASK_SYSTEM, false);
|
||||
EXPECT_EQ(TASK_COUNT - 2, queueSize());
|
||||
EXPECT_EQ(lastTaskPrev, taskQueueArray[TASK_COUNT - 3]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT - 2]); // NULL at end of queue
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT]);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
EXPECT_EQ(TASK_COUNT_UNITTEST - 2, taskQueueSize);
|
||||
EXPECT_EQ(lastTaskPrev, taskQueueArray[TASK_COUNT_UNITTEST - 3]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 2]); // NULL at end of queue
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
|
||||
|
||||
taskQueueArray[TASK_COUNT - 2] = 0;
|
||||
taskQueueArray[TASK_COUNT_UNITTEST - 2] = 0;
|
||||
setTaskEnabled(TASK_SYSTEM, true);
|
||||
EXPECT_EQ(TASK_COUNT - 1, queueSize());
|
||||
EXPECT_EQ(lastTaskPrev, taskQueueArray[TASK_COUNT - 2]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT]);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
EXPECT_EQ(TASK_COUNT_UNITTEST - 1, taskQueueSize);
|
||||
EXPECT_EQ(lastTaskPrev, taskQueueArray[TASK_COUNT_UNITTEST - 2]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
|
||||
|
||||
cfTaskInfo_t taskInfo;
|
||||
getTaskInfo(static_cast<cfTaskId_e>(TASK_COUNT - 1), &taskInfo);
|
||||
getTaskInfo(static_cast<cfTaskId_e>(TASK_COUNT_UNITTEST - 1), &taskInfo);
|
||||
EXPECT_EQ(false, taskInfo.isEnabled);
|
||||
setTaskEnabled(static_cast<cfTaskId_e>(TASK_COUNT - 1), true);
|
||||
EXPECT_EQ(TASK_COUNT, queueSize());
|
||||
EXPECT_EQ(lastTaskPrev, taskQueueArray[TASK_COUNT - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT]); // check no buffer overrun
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
setTaskEnabled(static_cast<cfTaskId_e>(TASK_COUNT_UNITTEST - 1), true);
|
||||
EXPECT_EQ(TASK_COUNT_UNITTEST, taskQueueSize);
|
||||
EXPECT_EQ(lastTaskPrev, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]); // check no buffer overrun
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
|
||||
|
||||
setTaskEnabled(TASK_SYSTEM, false);
|
||||
EXPECT_EQ(TASK_COUNT - 1, queueSize());
|
||||
//EXPECT_EQ(lastTaskPrev, taskQueueArray[TASK_COUNT - 3]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT]);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
EXPECT_EQ(TASK_COUNT_UNITTEST - 1, taskQueueSize);
|
||||
//EXPECT_EQ(lastTaskPrev, taskQueueArray[TASK_COUNT_UNITTEST - 3]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
|
||||
|
||||
setTaskEnabled(TASK_ACCEL, false);
|
||||
EXPECT_EQ(TASK_COUNT - 2, queueSize());
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT - 2]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT]);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
EXPECT_EQ(TASK_COUNT_UNITTEST - 2, taskQueueSize);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 2]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
|
||||
|
||||
setTaskEnabled(TASK_BATTERY, false);
|
||||
EXPECT_EQ(TASK_COUNT - 3, queueSize());
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT - 3]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT - 2]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT]);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT + 1]);
|
||||
setTaskEnabled(TASK_BATTERY_VOLTAGE, false);
|
||||
EXPECT_EQ(TASK_COUNT_UNITTEST - 3, taskQueueSize);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 3]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 2]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
|
||||
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]);
|
||||
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
|
||||
}
|
||||
|
||||
TEST(SchedulerUnittest, TestSchedulerInit)
|
||||
{
|
||||
schedulerInit();
|
||||
EXPECT_EQ(1, queueSize());
|
||||
EXPECT_EQ(1, taskQueueSize);
|
||||
EXPECT_EQ(&cfTasks[TASK_SYSTEM], queueFirst());
|
||||
}
|
||||
|
||||
|
@ -291,7 +331,7 @@ TEST(SchedulerUnittest, TestSingleTask)
|
|||
EXPECT_EQ(&cfTasks[TASK_GYROPID], unittest_scheduler_selectedTask);
|
||||
EXPECT_EQ(3000, cfTasks[TASK_GYROPID].taskLatestDeltaTime);
|
||||
EXPECT_EQ(4000, cfTasks[TASK_GYROPID].lastExecutedAt);
|
||||
EXPECT_EQ(pidLoopCheckerTime, cfTasks[TASK_GYROPID].totalExecutionTime);
|
||||
EXPECT_EQ(TEST_PID_LOOP_TIME, cfTasks[TASK_GYROPID].totalExecutionTime);
|
||||
// task has run, so its dynamic priority should have been set to zero
|
||||
EXPECT_EQ(0, cfTasks[TASK_GYROPID].dynamicPriority);
|
||||
}
|
||||
|
@ -309,7 +349,7 @@ TEST(SchedulerUnittest, TestTwoTasks)
|
|||
static const uint32_t startTime = 4000;
|
||||
simulatedTime = startTime;
|
||||
cfTasks[TASK_GYROPID].lastExecutedAt = simulatedTime;
|
||||
cfTasks[TASK_ACCEL].lastExecutedAt = cfTasks[TASK_GYROPID].lastExecutedAt - updateAccelerometerTime;
|
||||
cfTasks[TASK_ACCEL].lastExecutedAt = cfTasks[TASK_GYROPID].lastExecutedAt - TEST_UPDATE_ACCEL_TIME;
|
||||
EXPECT_EQ(0, cfTasks[TASK_ACCEL].taskAgeCycles);
|
||||
// run the scheduler
|
||||
scheduler();
|
||||
|
@ -332,9 +372,9 @@ TEST(SchedulerUnittest, TestTwoTasks)
|
|||
scheduler();
|
||||
EXPECT_EQ(&cfTasks[TASK_GYROPID], unittest_scheduler_selectedTask);
|
||||
EXPECT_EQ(1, unittest_scheduler_waitingTasks);
|
||||
EXPECT_EQ(5000 + pidLoopCheckerTime, simulatedTime);
|
||||
EXPECT_EQ(5000 + TEST_PID_LOOP_TIME, simulatedTime);
|
||||
|
||||
simulatedTime += 1000 - pidLoopCheckerTime;
|
||||
simulatedTime += 1000 - TEST_PID_LOOP_TIME;
|
||||
scheduler();
|
||||
// TASK_GYROPID should run again
|
||||
EXPECT_EQ(&cfTasks[TASK_GYROPID], unittest_scheduler_selectedTask);
|
||||
|
@ -351,57 +391,3 @@ TEST(SchedulerUnittest, TestTwoTasks)
|
|||
scheduler();
|
||||
EXPECT_EQ(&cfTasks[TASK_ACCEL], unittest_scheduler_selectedTask);
|
||||
}
|
||||
|
||||
TEST(SchedulerUnittest, TestRealTimeGuardInNoTaskRun)
|
||||
{
|
||||
// disable all tasks except TASK_GYROPID and TASK_SYSTEM
|
||||
for (int taskId=0; taskId < TASK_COUNT; ++taskId) {
|
||||
setTaskEnabled(static_cast<cfTaskId_e>(taskId), false);
|
||||
}
|
||||
setTaskEnabled(TASK_GYROPID, true);
|
||||
cfTasks[TASK_GYROPID].lastExecutedAt = 200000;
|
||||
simulatedTime = 200700;
|
||||
|
||||
setTaskEnabled(TASK_SYSTEM, true);
|
||||
cfTasks[TASK_SYSTEM].lastExecutedAt = 100000;
|
||||
|
||||
scheduler();
|
||||
|
||||
EXPECT_EQ(false, unittest_outsideRealtimeGuardInterval);
|
||||
EXPECT_EQ(300, unittest_scheduler_timeToNextRealtimeTask);
|
||||
|
||||
// Nothing should be scheduled in guard period
|
||||
EXPECT_EQ(NULL, unittest_scheduler_selectedTask);
|
||||
EXPECT_EQ(100000, cfTasks[TASK_SYSTEM].lastExecutedAt);
|
||||
|
||||
EXPECT_EQ(200000, cfTasks[TASK_GYROPID].lastExecutedAt);
|
||||
}
|
||||
|
||||
TEST(SchedulerUnittest, TestRealTimeGuardOutTaskRun)
|
||||
{
|
||||
// disable all tasks except TASK_GYROPID and TASK_SYSTEM
|
||||
for (int taskId=0; taskId < TASK_COUNT; ++taskId) {
|
||||
setTaskEnabled(static_cast<cfTaskId_e>(taskId), false);
|
||||
}
|
||||
setTaskEnabled(TASK_GYROPID, true);
|
||||
cfTasks[TASK_GYROPID].lastExecutedAt = 200000;
|
||||
simulatedTime = 200699;
|
||||
|
||||
setTaskEnabled(TASK_SYSTEM, true);
|
||||
cfTasks[TASK_SYSTEM].lastExecutedAt = 100000;
|
||||
|
||||
scheduler();
|
||||
|
||||
EXPECT_EQ(true, unittest_outsideRealtimeGuardInterval);
|
||||
EXPECT_EQ(301, unittest_scheduler_timeToNextRealtimeTask);
|
||||
|
||||
// System should be scheduled as not in guard period
|
||||
EXPECT_EQ(&cfTasks[TASK_SYSTEM], unittest_scheduler_selectedTask);
|
||||
EXPECT_EQ(200699, cfTasks[TASK_SYSTEM].lastExecutedAt);
|
||||
|
||||
EXPECT_EQ(200000, cfTasks[TASK_GYROPID].lastExecutedAt);
|
||||
}
|
||||
|
||||
// STUBS
|
||||
extern "C" {
|
||||
}
|
|
@ -17,9 +17,13 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define SCHEDULER_DELAY_LIMIT 1
|
||||
#define TASK_GYROPID_DESIRED_PERIOD 100
|
||||
|
||||
#define CMS
|
||||
#define CMS_MAX_DEVICE 4
|
||||
#define USE_FAKE_GYRO
|
||||
#define BEEPER
|
||||
#define BLACKBOX
|
||||
#define MAG
|
||||
#define BARO
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue