mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
Merge branch 'master' into gps_task_time
This commit is contained in:
commit
d7776cd583
173 changed files with 36427 additions and 13968 deletions
|
@ -20,9 +20,14 @@ MEMORY
|
|||
|
||||
|
||||
SYSTEM_MEMORY (r) : ORIGIN = 0x1FFF0000, LENGTH = 64K
|
||||
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 96K
|
||||
CCM (xrw) : ORIGIN = 0x20018000, LENGTH = 32K
|
||||
/* Below are the true lengths for normal and close coupled RAM
|
||||
* RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 96K
|
||||
* CCM (xrw) : ORIGIN = 0x20018000, LENGTH = 32K
|
||||
* Allow normal RAM overflow to occupy start of CCM, and only reserve 2560 bytes for vector table and stack in CCM
|
||||
* CCM is aligned to a 512 byte boundary
|
||||
*/
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128512
|
||||
CCM (xrw) : ORIGIN = 0x2001F600, LENGTH = 2560
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
|
|
|
@ -76,6 +76,8 @@ mcuTypeId_e getMcuTypeId(void)
|
|||
return MCU_TYPE_H7A3;
|
||||
#elif defined(STM32H723xx) || defined(STM32H725xx)
|
||||
return MCU_TYPE_H723_725;
|
||||
#elif defined(STM32G474xx)
|
||||
return MCU_TYPE_G474;
|
||||
#else
|
||||
return MCU_TYPE_UNKNOWN;
|
||||
#endif
|
||||
|
|
|
@ -59,6 +59,7 @@ typedef enum {
|
|||
MCU_TYPE_H743_REV_V,
|
||||
MCU_TYPE_H7A3,
|
||||
MCU_TYPE_H723_725,
|
||||
MCU_TYPE_G474,
|
||||
MCU_TYPE_UNKNOWN = 255,
|
||||
} mcuTypeId_e;
|
||||
|
||||
|
|
|
@ -308,6 +308,7 @@ static const char *mcuTypeNames[] = {
|
|||
"H743 (Rev.V)",
|
||||
"H7A3",
|
||||
"H723/H725",
|
||||
"G474",
|
||||
};
|
||||
|
||||
static const char *configurationStates[] = { "UNCONFIGURED", "CUSTOM DEFAULTS", "CONFIGURED" };
|
||||
|
@ -4664,7 +4665,7 @@ STATIC_UNIT_TESTED void cliSet(const char *cmdName, char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
const char *getMcuTypeById(mcuTypeId_e id)
|
||||
static const char *getMcuTypeById(mcuTypeId_e id)
|
||||
{
|
||||
if (id < MCU_TYPE_UNKNOWN) {
|
||||
return mcuTypeNames[id];
|
||||
|
|
|
@ -179,19 +179,6 @@ float scaleRangef(float x, float srcFrom, float srcTo, float destFrom, float des
|
|||
return (a / b) + destFrom;
|
||||
}
|
||||
|
||||
// Normalize a vector
|
||||
void normalizeV(struct fp_vector *src, struct fp_vector *dest)
|
||||
{
|
||||
float length;
|
||||
|
||||
length = sqrtf(src->X * src->X + src->Y * src->Y + src->Z * src->Z);
|
||||
if (length != 0) {
|
||||
dest->X = src->X / length;
|
||||
dest->Y = src->Y / length;
|
||||
dest->Z = src->Z / length;
|
||||
}
|
||||
}
|
||||
|
||||
void buildRotationMatrix(fp_angles_t *delta, fp_rotationMatrix_t *rotation)
|
||||
{
|
||||
float cosx, sinx, cosy, siny, cosz, sinz;
|
||||
|
@ -220,7 +207,7 @@ void buildRotationMatrix(fp_angles_t *delta, fp_rotationMatrix_t *rotation)
|
|||
rotation->m[2][Z] = cosy * cosx;
|
||||
}
|
||||
|
||||
FAST_CODE void applyRotation(float *v, fp_rotationMatrix_t *rotationMatrix)
|
||||
void applyMatrixRotation(float *v, fp_rotationMatrix_t *rotationMatrix)
|
||||
{
|
||||
struct fp_vector *vDest = (struct fp_vector *)v;
|
||||
struct fp_vector vTmp = *vDest;
|
||||
|
@ -230,18 +217,6 @@ FAST_CODE void applyRotation(float *v, fp_rotationMatrix_t *rotationMatrix)
|
|||
vDest->Z = (rotationMatrix->m[0][Z] * vTmp.X + rotationMatrix->m[1][Z] * vTmp.Y + rotationMatrix->m[2][Z] * vTmp.Z);
|
||||
}
|
||||
|
||||
// Rotate a vector *v by the euler angles defined by the 3-vector *delta.
|
||||
void rotateV(struct fp_vector *v, fp_angles_t *delta)
|
||||
{
|
||||
struct fp_vector v_tmp = *v;
|
||||
|
||||
fp_rotationMatrix_t rotationMatrix;
|
||||
|
||||
buildRotationMatrix(delta, &rotationMatrix);
|
||||
|
||||
applyRotation((float *)&v_tmp, &rotationMatrix);
|
||||
}
|
||||
|
||||
// Quick median filter implementation
|
||||
// (c) N. Devillard - 1998
|
||||
// http://ndevilla.free.fr/median/median.pdf
|
||||
|
|
|
@ -113,11 +113,8 @@ float degreesToRadians(int16_t degrees);
|
|||
int scaleRange(int x, int srcFrom, int srcTo, int destFrom, int destTo);
|
||||
float scaleRangef(float x, float srcFrom, float srcTo, float destFrom, float destTo);
|
||||
|
||||
void normalizeV(struct fp_vector *src, struct fp_vector *dest);
|
||||
|
||||
void rotateV(struct fp_vector *v, fp_angles_t *delta);
|
||||
void buildRotationMatrix(fp_angles_t *delta, fp_rotationMatrix_t *rotation);
|
||||
void applyRotation(float *v, fp_rotationMatrix_t *rotationMatrix);
|
||||
void applyMatrixRotation(float *v, fp_rotationMatrix_t *rotationMatrix);
|
||||
|
||||
int32_t quickMedianFilter3(int32_t * v);
|
||||
int32_t quickMedianFilter5(int32_t * v);
|
||||
|
|
|
@ -40,10 +40,10 @@
|
|||
|
||||
#define BMI270_FIFO_FRAME_SIZE 6
|
||||
|
||||
#define BMI270_CONFIG_SIZE 8192
|
||||
#define BMI270_CONFIG_SIZE 328
|
||||
|
||||
// Declaration for the device config (microcode) that must be uploaded to the sensor
|
||||
extern const uint8_t bmi270_config_file[BMI270_CONFIG_SIZE];
|
||||
extern const uint8_t bmi270_maximum_fifo_config_file[BMI270_CONFIG_SIZE];
|
||||
|
||||
#define BMI270_CHIP_ID 0x24
|
||||
|
||||
|
@ -174,7 +174,7 @@ static void bmi270UploadConfig(const busDevice_t *bus)
|
|||
// Transfer the config file
|
||||
IOLo(bus->busdev_u.spi.csnPin);
|
||||
spiTransferByte(bus->busdev_u.spi.instance, BMI270_REG_INIT_DATA);
|
||||
spiTransfer(bus->busdev_u.spi.instance, bmi270_config_file, NULL, sizeof(bmi270_config_file));
|
||||
spiTransfer(bus->busdev_u.spi.instance, bmi270_maximum_fifo_config_file, NULL, sizeof(bmi270_maximum_fifo_config_file));
|
||||
IOHi(bus->busdev_u.spi.csnPin);
|
||||
|
||||
delay(10);
|
||||
|
|
|
@ -118,16 +118,9 @@ static uint16_t FAST_DATA_ZERO_INIT dynNotchMaxFFT;
|
|||
static float FAST_DATA_ZERO_INIT smoothFactor;
|
||||
static uint8_t FAST_DATA_ZERO_INIT numSamples;
|
||||
|
||||
void gyroDataAnalyseInit(uint32_t targetLooptimeUs)
|
||||
void gyroDataAnalyseInit(gyroAnalyseState_t *state, uint32_t targetLooptimeUs)
|
||||
{
|
||||
#ifdef USE_MULTI_GYRO
|
||||
static bool gyroAnalyseInitialized;
|
||||
if (gyroAnalyseInitialized) {
|
||||
return;
|
||||
}
|
||||
gyroAnalyseInitialized = true;
|
||||
#endif
|
||||
|
||||
// initialise even if FEATURE_DYNAMIC_FILTER not set, since it may be set later
|
||||
dynNotchBandwidthHz = gyroConfig()->dyn_notch_bandwidth_hz;
|
||||
dynNotchMinHz = gyroConfig()->dyn_notch_min_hz;
|
||||
dynNotchMaxHz = MAX(2 * dynNotchMinHz, gyroConfig()->dyn_notch_max_hz);
|
||||
|
@ -152,12 +145,7 @@ void gyroDataAnalyseInit(uint32_t targetLooptimeUs)
|
|||
for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
sdftInit(&sdft[axis], sdftStartBin, sdftEndBin, numSamples);
|
||||
}
|
||||
}
|
||||
|
||||
void gyroDataAnalyseStateInit(gyroAnalyseState_t *state, uint32_t targetLooptimeUs)
|
||||
{
|
||||
// initialise even if FEATURE_DYNAMIC_FILTER not set, since it may be set later
|
||||
gyroDataAnalyseInit(targetLooptimeUs);
|
||||
state->maxSampleCount = numSamples;
|
||||
state->maxSampleCountRcp = 1.0f / state->maxSampleCount;
|
||||
|
||||
|
|
|
@ -42,7 +42,7 @@ typedef struct gyroAnalyseState_s {
|
|||
|
||||
} gyroAnalyseState_t;
|
||||
|
||||
void gyroDataAnalyseStateInit(gyroAnalyseState_t *state, uint32_t targetLooptimeUs);
|
||||
void gyroDataAnalyseInit(gyroAnalyseState_t *state, uint32_t targetLooptimeUs);
|
||||
void gyroDataAnalysePush(gyroAnalyseState_t *state, const uint8_t axis, const float sample);
|
||||
void gyroDataAnalyse(gyroAnalyseState_t *state);
|
||||
uint16_t getMaxFFT(void);
|
||||
|
|
|
@ -1057,16 +1057,24 @@ static void osdElementGpsCoordinate(osdElementParms_t *element)
|
|||
|
||||
static void osdElementGpsSats(osdElementParms_t *element)
|
||||
{
|
||||
int pos = tfp_sprintf(element->buff, "%c%c%2d", SYM_SAT_L, SYM_SAT_R, gpsSol.numSat);
|
||||
if (osdConfig()->gps_sats_show_hdop) { // add on the GPS module HDOP estimate
|
||||
element->buff[pos++] = ' ';
|
||||
osdPrintFloat(element->buff + pos, SYM_NONE, gpsSol.hdop / 100.0f, "", 1, true, SYM_NONE);
|
||||
if (!gpsIsHealthy()) {
|
||||
tfp_sprintf(element->buff, "%c%cNC", SYM_SAT_L, SYM_SAT_R);
|
||||
} else {
|
||||
int pos = tfp_sprintf(element->buff, "%c%c%2d", SYM_SAT_L, SYM_SAT_R, gpsSol.numSat);
|
||||
if (osdConfig()->gps_sats_show_hdop) { // add on the GPS module HDOP estimate
|
||||
element->buff[pos++] = ' ';
|
||||
osdPrintFloat(element->buff + pos, SYM_NONE, gpsSol.hdop / 100.0f, "", 1, true, SYM_NONE);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void osdElementGpsSpeed(osdElementParms_t *element)
|
||||
{
|
||||
tfp_sprintf(element->buff, "%c%3d%c", SYM_SPEED, osdGetSpeedToSelectedUnit(gpsConfig()->gps_use_3d_speed ? gpsSol.speed3d : gpsSol.groundSpeed), osdGetSpeedToSelectedUnitSymbol());
|
||||
if (STATE(GPS_FIX)) {
|
||||
tfp_sprintf(element->buff, "%c%3d%c", SYM_SPEED, osdGetSpeedToSelectedUnit(gpsConfig()->gps_use_3d_speed ? gpsSol.speed3d : gpsSol.groundSpeed), osdGetSpeedToSelectedUnitSymbol());
|
||||
} else {
|
||||
tfp_sprintf(element->buff, "%c%c%c", SYM_SPEED, SYM_HYPHEN, osdGetSpeedToSelectedUnitSymbol());
|
||||
}
|
||||
}
|
||||
|
||||
static void osdElementEfficiency(osdElementParms_t *element)
|
||||
|
|
|
@ -64,14 +64,14 @@ void initBoardAlignment(const boardAlignment_t *boardAlignment)
|
|||
buildRotationMatrix(&rotationAngles, &boardRotation);
|
||||
}
|
||||
|
||||
static FAST_CODE void alignBoard(float *vec)
|
||||
static void alignBoard(float *vec)
|
||||
{
|
||||
applyRotation(vec, &boardRotation);
|
||||
applyMatrixRotation(vec, &boardRotation);
|
||||
}
|
||||
|
||||
FAST_CODE_NOINLINE void alignSensorViaMatrix(float *dest, fp_rotationMatrix_t* sensorRotationMatrix)
|
||||
{
|
||||
applyRotation(dest, sensorRotationMatrix);
|
||||
applyMatrixRotation(dest, sensorRotationMatrix);
|
||||
|
||||
if (!standardBoardAlignment) {
|
||||
alignBoard(dest);
|
||||
|
|
|
@ -134,8 +134,8 @@ void pgResetFn_gyroConfig(gyroConfig_t *gyroConfig)
|
|||
gyroConfig->dyn_notch_min_hz = 150;
|
||||
gyroConfig->gyro_filter_debug_axis = FD_ROLL;
|
||||
gyroConfig->dyn_lpf_curve_expo = 5;
|
||||
gyroConfig->simplified_gyro_filter = false;
|
||||
gyroConfig->simplified_gyro_filter_multiplier = SIMPLIFIED_TUNING_DEFAULT;
|
||||
gyroConfig->simplified_gyro_filter = false;
|
||||
gyroConfig->simplified_gyro_filter_multiplier = SIMPLIFIED_TUNING_DEFAULT;
|
||||
}
|
||||
|
||||
#ifdef USE_GYRO_DATA_ANALYSE
|
||||
|
|
|
@ -166,11 +166,11 @@ enum {
|
|||
};
|
||||
|
||||
typedef struct gyroConfig_s {
|
||||
uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default.
|
||||
uint8_t gyro_hardware_lpf; // gyro DLPF setting
|
||||
uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default.
|
||||
uint8_t gyro_hardware_lpf; // gyro DLPF setting
|
||||
|
||||
uint8_t gyro_high_fsr;
|
||||
uint8_t gyro_to_use;
|
||||
uint8_t gyro_high_fsr;
|
||||
uint8_t gyro_to_use;
|
||||
|
||||
uint16_t gyro_lowpass_hz;
|
||||
uint16_t gyro_lowpass2_hz;
|
||||
|
@ -179,15 +179,15 @@ typedef struct gyroConfig_s {
|
|||
uint16_t gyro_soft_notch_cutoff_1;
|
||||
uint16_t gyro_soft_notch_hz_2;
|
||||
uint16_t gyro_soft_notch_cutoff_2;
|
||||
int16_t gyro_offset_yaw;
|
||||
uint8_t checkOverflow;
|
||||
int16_t gyro_offset_yaw;
|
||||
uint8_t checkOverflow;
|
||||
|
||||
// Lowpass primary/secondary
|
||||
uint8_t gyro_lowpass_type;
|
||||
uint8_t gyro_lowpass2_type;
|
||||
uint8_t gyro_lowpass_type;
|
||||
uint8_t gyro_lowpass2_type;
|
||||
|
||||
uint8_t yaw_spin_recovery;
|
||||
int16_t yaw_spin_threshold;
|
||||
uint8_t yaw_spin_recovery;
|
||||
int16_t yaw_spin_threshold;
|
||||
|
||||
uint16_t gyroCalibrationDuration; // Gyro calibration duration in 1/100 second
|
||||
|
||||
|
@ -195,16 +195,16 @@ typedef struct gyroConfig_s {
|
|||
uint16_t dyn_lpf_gyro_max_hz;
|
||||
|
||||
uint16_t dyn_notch_max_hz;
|
||||
uint8_t dyn_notch_count;
|
||||
uint8_t dyn_notch_count;
|
||||
uint16_t dyn_notch_bandwidth_hz;
|
||||
uint16_t dyn_notch_min_hz;
|
||||
|
||||
uint8_t gyro_filter_debug_axis;
|
||||
uint8_t gyro_filter_debug_axis;
|
||||
|
||||
uint8_t gyrosDetected; // What gyros should detection be attempted for on startup. Automatically set on first startup.
|
||||
uint8_t dyn_lpf_curve_expo; // set the curve for dynamic gyro lowpass filter
|
||||
uint8_t simplified_gyro_filter;
|
||||
uint8_t simplified_gyro_filter_multiplier;
|
||||
uint8_t simplified_gyro_filter;
|
||||
uint8_t simplified_gyro_filter_multiplier;
|
||||
} gyroConfig_t;
|
||||
|
||||
PG_DECLARE(gyroConfig_t, gyroConfig);
|
||||
|
|
|
@ -264,7 +264,7 @@ void gyroInitFilters(void)
|
|||
dynLpfFilterInit();
|
||||
#endif
|
||||
#ifdef USE_GYRO_DATA_ANALYSE
|
||||
gyroDataAnalyseStateInit(&gyro.gyroAnalyseState, gyro.targetLooptime);
|
||||
gyroDataAnalyseInit(&gyro.gyroAnalyseState, gyro.targetLooptime);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -11,7 +11,7 @@ TARGET_SRC += \
|
|||
drivers/accgyro/accgyro_spi_mpu6000.c \
|
||||
drivers/accgyro/accgyro_spi_lsm6dso_init.c \
|
||||
drivers/accgyro/accgyro_spi_lsm6dso.c \
|
||||
$(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270.c \
|
||||
$(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \
|
||||
drivers/accgyro/accgyro_spi_bmi270.c \
|
||||
drivers/barometer/barometer_dps310.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
|
@ -21,4 +21,4 @@ TARGET_SRC += \
|
|||
drivers/compass/compass_lis3mdl.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_hal.c \
|
||||
drivers/max7456.c
|
||||
drivers/max7456.c
|
||||
|
|
|
@ -11,7 +11,7 @@ TARGET_SRC += \
|
|||
drivers/accgyro/accgyro_spi_mpu6000.c \
|
||||
drivers/accgyro/accgyro_spi_lsm6dso_init.c \
|
||||
drivers/accgyro/accgyro_spi_lsm6dso.c \
|
||||
$(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270.c \
|
||||
$(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \
|
||||
drivers/accgyro/accgyro_spi_bmi270.c \
|
||||
drivers/barometer/barometer_dps310.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
|
@ -21,4 +21,4 @@ TARGET_SRC += \
|
|||
drivers/compass/compass_lis3mdl.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_hal.c \
|
||||
drivers/max7456.c
|
||||
drivers/max7456.c
|
||||
|
|
|
@ -35,7 +35,7 @@ endif
|
|||
|
||||
TARGET_SRC = \
|
||||
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
|
||||
$(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270.c \
|
||||
$(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \
|
||||
$(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \
|
||||
$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
|
||||
drivers/max7456.c \
|
||||
|
|
|
@ -445,6 +445,7 @@ extern "C" {
|
|||
bool areMotorsRunning(void){ return true; }
|
||||
bool pidOsdAntiGravityActive(void) { return false; }
|
||||
bool failsafeIsActive(void) { return false; }
|
||||
bool gpsIsHealthy(void) { return true; }
|
||||
bool gpsRescueIsConfigured(void) { return false; }
|
||||
int8_t calculateThrottlePercent(void) { return 0; }
|
||||
uint32_t persistentObjectRead(persistentObjectId_e) { return 0; }
|
||||
|
|
|
@ -202,29 +202,6 @@ void expectVectorsAreEqual(struct fp_vector *a, struct fp_vector *b, float absTo
|
|||
EXPECT_NEAR(a->Z, b->Z, absTol);
|
||||
}
|
||||
|
||||
TEST(MathsUnittest, TestRotateVectorWithNoAngle)
|
||||
{
|
||||
fp_vector vector = {1.0f, 0.0f, 0.0f};
|
||||
fp_angles_t euler_angles = {.raw={0.0f, 0.0f, 0.0f}};
|
||||
|
||||
rotateV(&vector, &euler_angles);
|
||||
fp_vector expected_result = {1.0f, 0.0f, 0.0f};
|
||||
|
||||
expectVectorsAreEqual(&vector, &expected_result, 1e-5);
|
||||
}
|
||||
|
||||
TEST(MathsUnittest, TestRotateVectorAroundAxis)
|
||||
{
|
||||
// Rotate a vector <1, 0, 0> around an each axis x y and z.
|
||||
fp_vector vector = {1.0f, 0.0f, 0.0f};
|
||||
fp_angles_t euler_angles = {.raw={90.0f, 0.0f, 0.0f}};
|
||||
|
||||
rotateV(&vector, &euler_angles);
|
||||
fp_vector expected_result = {1.0f, 0.0f, 0.0f};
|
||||
|
||||
expectVectorsAreEqual(&vector, &expected_result, 1e-5);
|
||||
}
|
||||
|
||||
#if defined(FAST_MATH) || defined(VERY_FAST_MATH)
|
||||
TEST(MathsUnittest, TestFastTrigonometrySinCos)
|
||||
{
|
||||
|
|
|
@ -104,6 +104,7 @@ extern "C" {
|
|||
int32_t simulationAltitude;
|
||||
int32_t simulationVerticalSpeed;
|
||||
uint16_t simulationCoreTemperature;
|
||||
bool simulationGpsHealthy;
|
||||
}
|
||||
|
||||
uint32_t simulationFeatureFlags = FEATURE_GPS;
|
||||
|
@ -130,6 +131,7 @@ void setDefaultSimulationState()
|
|||
simulationAltitude = 0;
|
||||
simulationVerticalSpeed = 0;
|
||||
simulationCoreTemperature = 0;
|
||||
simulationGpsHealthy = false;
|
||||
|
||||
rcData[PITCH] = 1500;
|
||||
|
||||
|
@ -1134,6 +1136,74 @@ TEST_F(OsdTest, TestConvertTemperatureUnits)
|
|||
EXPECT_EQ(osdConvertTemperatureToSelectedUnit(41), 106);
|
||||
}
|
||||
|
||||
TEST_F(OsdTest, TestGpsElements)
|
||||
{
|
||||
// given
|
||||
osdElementConfigMutable()->item_pos[OSD_GPS_SATS] = OSD_POS(2, 4) | OSD_PROFILE_1_FLAG;
|
||||
|
||||
sensorsSet(SENSOR_GPS);
|
||||
osdAnalyzeActiveElements();
|
||||
|
||||
// when
|
||||
simulationGpsHealthy = false;
|
||||
gpsSol.numSat = 0;
|
||||
|
||||
displayClearScreen(&testDisplayPort);
|
||||
osdRefresh(simulationTime);
|
||||
|
||||
// then
|
||||
// Sat indicator should blink and show "NC"
|
||||
for (int i = 0; i < 15; i++) {
|
||||
// Blinking should happen at 5Hz
|
||||
simulationTime += 0.2e6;
|
||||
osdRefresh(simulationTime);
|
||||
|
||||
if (i % 2 == 0) {
|
||||
displayPortTestBufferSubstring(2, 4, "%c%cNC", SYM_SAT_L, SYM_SAT_R);
|
||||
} else {
|
||||
displayPortTestBufferIsEmpty();
|
||||
}
|
||||
}
|
||||
|
||||
// when
|
||||
simulationGpsHealthy = true;
|
||||
gpsSol.numSat = 0;
|
||||
|
||||
displayClearScreen(&testDisplayPort);
|
||||
osdRefresh(simulationTime);
|
||||
|
||||
// then
|
||||
// Sat indicator should blink and show "0"
|
||||
for (int i = 0; i < 15; i++) {
|
||||
// Blinking should happen at 5Hz
|
||||
simulationTime += 0.2e6;
|
||||
osdRefresh(simulationTime);
|
||||
|
||||
if (i % 2 == 0) {
|
||||
displayPortTestBufferSubstring(2, 4, "%c%c 0", SYM_SAT_L, SYM_SAT_R);
|
||||
} else {
|
||||
displayPortTestBufferIsEmpty();
|
||||
}
|
||||
}
|
||||
|
||||
// when
|
||||
simulationGpsHealthy = true;
|
||||
gpsSol.numSat = 10;
|
||||
|
||||
displayClearScreen(&testDisplayPort);
|
||||
osdRefresh(simulationTime);
|
||||
|
||||
// then
|
||||
// Sat indicator should show "10" without flashing
|
||||
for (int i = 0; i < 15; i++) {
|
||||
// Blinking should happen at 5Hz
|
||||
simulationTime += 0.2e6;
|
||||
osdRefresh(simulationTime);
|
||||
|
||||
displayPortTestBufferSubstring(2, 4, "%c%c10", SYM_SAT_L, SYM_SAT_R);
|
||||
}
|
||||
}
|
||||
|
||||
// STUBS
|
||||
extern "C" {
|
||||
bool featureIsEnabled(uint32_t f) { return simulationFeatureFlags & f; }
|
||||
|
@ -1242,6 +1312,7 @@ extern "C" {
|
|||
bool pidOsdAntiGravityActive(void) { return false; }
|
||||
bool failsafeIsActive(void) { return false; }
|
||||
bool gpsRescueIsConfigured(void) { return false; }
|
||||
bool gpsIsHealthy(void) { return simulationGpsHealthy; }
|
||||
int8_t calculateThrottlePercent(void) { return 0; }
|
||||
uint32_t persistentObjectRead(persistentObjectId_e) { return 0; }
|
||||
void persistentObjectWrite(persistentObjectId_e, uint32_t) {}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue