Fix Blackbox P interval (#5645)
This commit is contained in:
parent
4b3ada82bf
commit
802edf236b
|
@ -82,7 +82,7 @@
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 1);
|
PG_REGISTER_WITH_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 1);
|
||||||
|
|
||||||
PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
|
PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
|
||||||
.p_denom = 32,
|
.p_ratio = 32,
|
||||||
.device = DEFAULT_BLACKBOX_DEVICE,
|
.device = DEFAULT_BLACKBOX_DEVICE,
|
||||||
.record_acc = 1,
|
.record_acc = 1,
|
||||||
.mode = BLACKBOX_MODE_NORMAL
|
.mode = BLACKBOX_MODE_NORMAL
|
||||||
|
@ -384,7 +384,7 @@ bool blackboxMayEditConfig(void)
|
||||||
|
|
||||||
static bool blackboxIsOnlyLoggingIntraframes(void)
|
static bool blackboxIsOnlyLoggingIntraframes(void)
|
||||||
{
|
{
|
||||||
return blackboxConfig()->p_denom == 0;
|
return blackboxConfig()->p_ratio == 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
||||||
|
@ -442,7 +442,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
||||||
return rxConfig()->rssi_channel > 0 || feature(FEATURE_RSSI_ADC);
|
return rxConfig()->rssi_channel > 0 || feature(FEATURE_RSSI_ADC);
|
||||||
|
|
||||||
case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME:
|
case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME:
|
||||||
return blackboxConfig()->p_denom != 1;
|
return blackboxConfig()->p_ratio != 1;
|
||||||
|
|
||||||
case FLIGHT_LOG_FIELD_CONDITION_ACC:
|
case FLIGHT_LOG_FIELD_CONDITION_ACC:
|
||||||
return sensors(SENSOR_ACC) && blackboxConfig()->record_acc;
|
return sensors(SENSOR_ACC) && blackboxConfig()->record_acc;
|
||||||
|
@ -1196,8 +1196,8 @@ static bool blackboxWriteSysinfo(void)
|
||||||
BLACKBOX_PRINT_HEADER_LINE("Log start datetime", "%s", blackboxGetStartDateTime(buf));
|
BLACKBOX_PRINT_HEADER_LINE("Log start datetime", "%s", blackboxGetStartDateTime(buf));
|
||||||
BLACKBOX_PRINT_HEADER_LINE("Craft name", "%s", pilotConfig()->name);
|
BLACKBOX_PRINT_HEADER_LINE("Craft name", "%s", pilotConfig()->name);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("I interval", "%d", blackboxIInterval);
|
BLACKBOX_PRINT_HEADER_LINE("I interval", "%d", blackboxIInterval);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("P interval", "%d/%d", blackboxGetRateNum(), blackboxGetRateDenom());
|
BLACKBOX_PRINT_HEADER_LINE("P interval", "%d", blackboxPInterval);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("P denom", "%d", blackboxConfig()->p_denom);
|
BLACKBOX_PRINT_HEADER_LINE("P ratio", "%d", blackboxConfig()->p_ratio);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("minthrottle", "%d", motorConfig()->minthrottle);
|
BLACKBOX_PRINT_HEADER_LINE("minthrottle", "%d", motorConfig()->minthrottle);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("maxthrottle", "%d", motorConfig()->maxthrottle);
|
BLACKBOX_PRINT_HEADER_LINE("maxthrottle", "%d", motorConfig()->maxthrottle);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("gyro_scale","0x%x", castFloatBytesToInt(1.0f));
|
BLACKBOX_PRINT_HEADER_LINE("gyro_scale","0x%x", castFloatBytesToInt(1.0f));
|
||||||
|
@ -1397,7 +1397,7 @@ static void blackboxCheckAndLogFlightMode(void)
|
||||||
|
|
||||||
STATIC_UNIT_TESTED bool blackboxShouldLogPFrame(void)
|
STATIC_UNIT_TESTED bool blackboxShouldLogPFrame(void)
|
||||||
{
|
{
|
||||||
return blackboxPFrameIndex == 0 && blackboxConfig()->p_denom != 0;
|
return blackboxPFrameIndex == 0 && blackboxConfig()->p_ratio != 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
STATIC_UNIT_TESTED bool blackboxShouldLogIFrame(void)
|
STATIC_UNIT_TESTED bool blackboxShouldLogIFrame(void)
|
||||||
|
@ -1695,14 +1695,10 @@ int blackboxCalculatePDenom(int rateNum, int rateDenom)
|
||||||
return blackboxIInterval * rateNum / rateDenom;
|
return blackboxIInterval * rateNum / rateDenom;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t blackboxGetRateNum(void)
|
|
||||||
{
|
|
||||||
return blackboxGetRateDenom() * blackboxConfig()->p_denom / blackboxIInterval;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t blackboxGetRateDenom(void)
|
uint8_t blackboxGetRateDenom(void)
|
||||||
{
|
{
|
||||||
return gcd(blackboxIInterval, blackboxPInterval);
|
return blackboxPInterval;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -1721,14 +1717,14 @@ void blackboxInit(void)
|
||||||
} else {
|
} else {
|
||||||
blackboxIInterval = (uint16_t)(32 * 1000 / gyro.targetLooptime);
|
blackboxIInterval = (uint16_t)(32 * 1000 / gyro.targetLooptime);
|
||||||
}
|
}
|
||||||
// by default p_denom is 32 and a P-frame is written every 1ms
|
// by default p_ratio is 32 and a P-frame is written every 1ms
|
||||||
// if p_denom is zero then no P-frames are logged
|
// if p_ratio is zero then no P-frames are logged
|
||||||
if (blackboxConfig()->p_denom == 0) {
|
if (blackboxConfig()->p_ratio == 0) {
|
||||||
blackboxPInterval = 0; // blackboxPInterval not used when p_denom is zero, so just set it to zero
|
blackboxPInterval = 0; // blackboxPInterval not used when p_ratio is zero, so just set it to zero
|
||||||
} else if (blackboxConfig()->p_denom > blackboxIInterval && blackboxIInterval >= 32) {
|
} else if (blackboxConfig()->p_ratio > blackboxIInterval && blackboxIInterval >= 32) {
|
||||||
blackboxPInterval = 1;
|
blackboxPInterval = 1;
|
||||||
} else {
|
} else {
|
||||||
blackboxPInterval = blackboxIInterval / blackboxConfig()->p_denom;
|
blackboxPInterval = blackboxIInterval / blackboxConfig()->p_ratio;
|
||||||
}
|
}
|
||||||
if (blackboxConfig()->device) {
|
if (blackboxConfig()->device) {
|
||||||
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
||||||
|
|
|
@ -48,7 +48,7 @@ typedef enum FlightLogEvent {
|
||||||
} FlightLogEvent;
|
} FlightLogEvent;
|
||||||
|
|
||||||
typedef struct blackboxConfig_s {
|
typedef struct blackboxConfig_s {
|
||||||
uint16_t p_denom; // I-frame interval / P-frame interval
|
uint16_t p_ratio; // I-frame interval / P-frame interval
|
||||||
uint8_t device;
|
uint8_t device;
|
||||||
uint8_t record_acc;
|
uint8_t record_acc;
|
||||||
uint8_t mode;
|
uint8_t mode;
|
||||||
|
@ -63,7 +63,6 @@ void blackboxInit(void);
|
||||||
void blackboxUpdate(timeUs_t currentTimeUs);
|
void blackboxUpdate(timeUs_t currentTimeUs);
|
||||||
void blackboxSetStartDateTime(const char *dateTime, timeMs_t timeNowMs);
|
void blackboxSetStartDateTime(const char *dateTime, timeMs_t timeNowMs);
|
||||||
int blackboxCalculatePDenom(int rateNum, int rateDenom);
|
int blackboxCalculatePDenom(int rateNum, int rateDenom);
|
||||||
uint8_t blackboxGetRateNum(void);
|
|
||||||
uint8_t blackboxGetRateDenom(void);
|
uint8_t blackboxGetRateDenom(void);
|
||||||
void blackboxValidateConfig(void);
|
void blackboxValidateConfig(void);
|
||||||
void blackboxFinish(void);
|
void blackboxFinish(void);
|
||||||
|
|
|
@ -61,7 +61,7 @@ static const char * const cmsx_BlackboxDeviceNames[] = {
|
||||||
"SERIAL"
|
"SERIAL"
|
||||||
};
|
};
|
||||||
|
|
||||||
static uint16_t blackboxConfig_p_denom;
|
static uint16_t blackboxConfig_p_ratio;
|
||||||
|
|
||||||
static uint8_t cmsx_BlackboxDevice;
|
static uint8_t cmsx_BlackboxDevice;
|
||||||
static OSD_TAB_t cmsx_BlackboxDeviceTable = { &cmsx_BlackboxDevice, 2, cmsx_BlackboxDeviceNames };
|
static OSD_TAB_t cmsx_BlackboxDeviceTable = { &cmsx_BlackboxDevice, 2, cmsx_BlackboxDeviceNames };
|
||||||
|
@ -172,7 +172,7 @@ static long cmsx_Blackbox_onEnter(void)
|
||||||
cmsx_Blackbox_GetDeviceStatus();
|
cmsx_Blackbox_GetDeviceStatus();
|
||||||
cmsx_BlackboxDevice = blackboxConfig()->device;
|
cmsx_BlackboxDevice = blackboxConfig()->device;
|
||||||
|
|
||||||
blackboxConfig_p_denom = blackboxConfig()->p_denom;
|
blackboxConfig_p_ratio = blackboxConfig()->p_ratio;
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -184,7 +184,7 @@ static long cmsx_Blackbox_onExit(const OSD_Entry *self)
|
||||||
blackboxConfigMutable()->device = cmsx_BlackboxDevice;
|
blackboxConfigMutable()->device = cmsx_BlackboxDevice;
|
||||||
blackboxValidateConfig();
|
blackboxValidateConfig();
|
||||||
}
|
}
|
||||||
blackboxConfigMutable()->p_denom = blackboxConfig_p_denom;
|
blackboxConfigMutable()->p_ratio = blackboxConfig_p_ratio;
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -195,7 +195,7 @@ static OSD_Entry cmsx_menuBlackboxEntries[] =
|
||||||
{ "(STATUS)", OME_String, NULL, &cmsx_BlackboxStatus, 0 },
|
{ "(STATUS)", OME_String, NULL, &cmsx_BlackboxStatus, 0 },
|
||||||
{ "(USED)", OME_String, NULL, &cmsx_BlackboxDeviceStorageUsed, 0 },
|
{ "(USED)", OME_String, NULL, &cmsx_BlackboxDeviceStorageUsed, 0 },
|
||||||
{ "(FREE)", OME_String, NULL, &cmsx_BlackboxDeviceStorageFree, 0 },
|
{ "(FREE)", OME_String, NULL, &cmsx_BlackboxDeviceStorageFree, 0 },
|
||||||
{ "P DENOM", OME_UINT16, NULL, &(OSD_UINT16_t){ &blackboxConfig_p_denom, 1, INT16_MAX, 1 },0 },
|
{ "P RATIO", OME_UINT16, NULL, &(OSD_UINT16_t){ &blackboxConfig_p_ratio, 1, INT16_MAX, 1 },0 },
|
||||||
|
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
{ "ERASE FLASH", OME_Funcall, cmsx_EraseFlash, NULL, 0 },
|
{ "ERASE FLASH", OME_Funcall, cmsx_EraseFlash, NULL, 0 },
|
||||||
|
|
|
@ -1146,9 +1146,9 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
|
||||||
#ifdef USE_BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
sbufWriteU8(dst, 1); //Blackbox supported
|
sbufWriteU8(dst, 1); //Blackbox supported
|
||||||
sbufWriteU8(dst, blackboxConfig()->device);
|
sbufWriteU8(dst, blackboxConfig()->device);
|
||||||
sbufWriteU8(dst, blackboxGetRateNum());
|
sbufWriteU8(dst, 1); // Rate numerator, not used anymore
|
||||||
sbufWriteU8(dst, blackboxGetRateDenom());
|
sbufWriteU8(dst, blackboxGetRateDenom());
|
||||||
sbufWriteU16(dst, blackboxConfig()->p_denom);
|
sbufWriteU16(dst, blackboxConfig()->p_ratio);
|
||||||
#else
|
#else
|
||||||
sbufWriteU8(dst, 0); // Blackbox not supported
|
sbufWriteU8(dst, 0); // Blackbox not supported
|
||||||
sbufWriteU8(dst, 0);
|
sbufWriteU8(dst, 0);
|
||||||
|
@ -1751,11 +1751,11 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
const int rateNum = sbufReadU8(src); // was rate_num
|
const int rateNum = sbufReadU8(src); // was rate_num
|
||||||
const int rateDenom = sbufReadU8(src); // was rate_denom
|
const int rateDenom = sbufReadU8(src); // was rate_denom
|
||||||
if (sbufBytesRemaining(src) >= 2) {
|
if (sbufBytesRemaining(src) >= 2) {
|
||||||
// p_denom specified, so use it directly
|
// p_ratio specified, so use it directly
|
||||||
blackboxConfigMutable()->p_denom = sbufReadU16(src);
|
blackboxConfigMutable()->p_ratio = sbufReadU16(src);
|
||||||
} else {
|
} else {
|
||||||
// p_denom not specified in MSP, so calculate it from old rateNum and rateDenom
|
// p_ratio not specified in MSP, so calculate it from old rateNum and rateDenom
|
||||||
blackboxConfigMutable()->p_denom = blackboxCalculatePDenom(rateNum, rateDenom);
|
blackboxConfigMutable()->p_ratio = blackboxCalculatePDenom(rateNum, rateDenom);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -516,7 +516,7 @@ const clivalue_t valueTable[] = {
|
||||||
|
|
||||||
// PG_BLACKBOX_CONFIG
|
// PG_BLACKBOX_CONFIG
|
||||||
#ifdef USE_BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
{ "blackbox_p_ratio", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, INT16_MAX }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, p_denom) },
|
{ "blackbox_p_ratio", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, INT16_MAX }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, p_ratio) },
|
||||||
{ "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_DEVICE }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, device) },
|
{ "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_DEVICE }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, device) },
|
||||||
{ "blackbox_record_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, record_acc) },
|
{ "blackbox_record_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, record_acc) },
|
||||||
{ "blackbox_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_MODE }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, mode) },
|
{ "blackbox_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_MODE }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, mode) },
|
||||||
|
|
|
@ -55,7 +55,7 @@ gyroDev_t gyroDev;
|
||||||
|
|
||||||
TEST(BlackboxTest, TestInitIntervals)
|
TEST(BlackboxTest, TestInitIntervals)
|
||||||
{
|
{
|
||||||
blackboxConfigMutable()->p_denom = 32;
|
blackboxConfigMutable()->p_ratio = 32;
|
||||||
// 250Hz PIDloop
|
// 250Hz PIDloop
|
||||||
gyro.targetLooptime = 4000;
|
gyro.targetLooptime = 4000;
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
|
@ -123,7 +123,7 @@ TEST(BlackboxTest, TestInitIntervals)
|
||||||
|
|
||||||
TEST(BlackboxTest, Test_500Hz)
|
TEST(BlackboxTest, Test_500Hz)
|
||||||
{
|
{
|
||||||
blackboxConfigMutable()->p_denom = 32;
|
blackboxConfigMutable()->p_ratio = 32;
|
||||||
// 500Hz PIDloop
|
// 500Hz PIDloop
|
||||||
gyro.targetLooptime = 2000;
|
gyro.targetLooptime = 2000;
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
|
@ -141,7 +141,7 @@ TEST(BlackboxTest, Test_500Hz)
|
||||||
|
|
||||||
TEST(BlackboxTest, Test_1kHz)
|
TEST(BlackboxTest, Test_1kHz)
|
||||||
{
|
{
|
||||||
blackboxConfigMutable()->p_denom = 32;
|
blackboxConfigMutable()->p_ratio = 32;
|
||||||
// 1kHz PIDloop
|
// 1kHz PIDloop
|
||||||
gyro.targetLooptime = 1000;
|
gyro.targetLooptime = 1000;
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
|
@ -167,7 +167,7 @@ TEST(BlackboxTest, Test_1kHz)
|
||||||
|
|
||||||
TEST(BlackboxTest, Test_2kHz)
|
TEST(BlackboxTest, Test_2kHz)
|
||||||
{
|
{
|
||||||
blackboxConfigMutable()->p_denom = 32;
|
blackboxConfigMutable()->p_ratio = 32;
|
||||||
// 2kHz PIDloop
|
// 2kHz PIDloop
|
||||||
gyro.targetLooptime = 500;
|
gyro.targetLooptime = 500;
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
|
@ -200,7 +200,7 @@ TEST(BlackboxTest, Test_2kHz)
|
||||||
|
|
||||||
TEST(BlackboxTest, Test_8kHz)
|
TEST(BlackboxTest, Test_8kHz)
|
||||||
{
|
{
|
||||||
blackboxConfigMutable()->p_denom = 32;
|
blackboxConfigMutable()->p_ratio = 32;
|
||||||
// 8kHz PIDloop
|
// 8kHz PIDloop
|
||||||
gyro.targetLooptime = 125;
|
gyro.targetLooptime = 125;
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
|
@ -223,9 +223,9 @@ TEST(BlackboxTest, Test_8kHz)
|
||||||
EXPECT_EQ(true, blackboxShouldLogPFrame());
|
EXPECT_EQ(true, blackboxShouldLogPFrame());
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST(BlackboxTest, Test_zero_p_denom)
|
TEST(BlackboxTest, Test_zero_p_ratio)
|
||||||
{
|
{
|
||||||
blackboxConfigMutable()->p_denom = 0;
|
blackboxConfigMutable()->p_ratio = 0;
|
||||||
// 1kHz PIDloop
|
// 1kHz PIDloop
|
||||||
gyro.targetLooptime = 1000;
|
gyro.targetLooptime = 1000;
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
|
@ -246,9 +246,9 @@ TEST(BlackboxTest, Test_zero_p_denom)
|
||||||
|
|
||||||
TEST(BlackboxTest, Test_CalculatePDenom)
|
TEST(BlackboxTest, Test_CalculatePDenom)
|
||||||
{
|
{
|
||||||
blackboxConfigMutable()->p_denom = 0;
|
blackboxConfigMutable()->p_ratio = 0;
|
||||||
// note I-frame is logged every 32ms regardless of PIDloop rate
|
// note I-frame is logged every 32ms regardless of PIDloop rate
|
||||||
// so p_denom is 32 when blackbox logging rate is 1kHz
|
// so p_ratio is 32 when blackbox logging rate is 1kHz
|
||||||
|
|
||||||
// 1kHz PIDloop
|
// 1kHz PIDloop
|
||||||
gyro.targetLooptime = 1000;
|
gyro.targetLooptime = 1000;
|
||||||
|
@ -290,57 +290,65 @@ TEST(BlackboxTest, Test_CalculateRates)
|
||||||
{
|
{
|
||||||
// 1kHz PIDloop
|
// 1kHz PIDloop
|
||||||
gyro.targetLooptime = 1000;
|
gyro.targetLooptime = 1000;
|
||||||
blackboxConfigMutable()->p_denom = 32;
|
blackboxConfigMutable()->p_ratio = 32;
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
EXPECT_EQ(32, blackboxIInterval);
|
EXPECT_EQ(32, blackboxIInterval);
|
||||||
EXPECT_EQ(1, blackboxPInterval);
|
EXPECT_EQ(1, blackboxPInterval);
|
||||||
EXPECT_EQ(1, blackboxGetRateNum());
|
|
||||||
EXPECT_EQ(1, blackboxGetRateDenom());
|
EXPECT_EQ(1, blackboxGetRateDenom());
|
||||||
|
|
||||||
blackboxConfigMutable()->p_denom = 16;
|
blackboxConfigMutable()->p_ratio = 16;
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
EXPECT_EQ(32, blackboxIInterval);
|
EXPECT_EQ(32, blackboxIInterval);
|
||||||
EXPECT_EQ(2, blackboxPInterval);
|
EXPECT_EQ(2, blackboxPInterval);
|
||||||
EXPECT_EQ(1, blackboxGetRateNum());
|
|
||||||
EXPECT_EQ(2, blackboxGetRateDenom());
|
EXPECT_EQ(2, blackboxGetRateDenom());
|
||||||
|
|
||||||
blackboxConfigMutable()->p_denom = 8;
|
blackboxConfigMutable()->p_ratio = 8;
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
EXPECT_EQ(32, blackboxIInterval);
|
EXPECT_EQ(32, blackboxIInterval);
|
||||||
EXPECT_EQ(4, blackboxPInterval);
|
EXPECT_EQ(4, blackboxPInterval);
|
||||||
EXPECT_EQ(1, blackboxGetRateNum());
|
|
||||||
EXPECT_EQ(4, blackboxGetRateDenom());
|
EXPECT_EQ(4, blackboxGetRateDenom());
|
||||||
|
|
||||||
|
|
||||||
// 8kHz PIDloop
|
// 8kHz PIDloop
|
||||||
gyro.targetLooptime = 125;
|
gyro.targetLooptime = 125;
|
||||||
blackboxConfigMutable()->p_denom = 32; // 1kHz logging
|
blackboxConfigMutable()->p_ratio = 32; // 1kHz logging
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
EXPECT_EQ(256, blackboxIInterval);
|
EXPECT_EQ(256, blackboxIInterval);
|
||||||
EXPECT_EQ(8, blackboxPInterval);
|
EXPECT_EQ(8, blackboxPInterval);
|
||||||
EXPECT_EQ(1, blackboxGetRateNum());
|
|
||||||
EXPECT_EQ(8, blackboxGetRateDenom());
|
EXPECT_EQ(8, blackboxGetRateDenom());
|
||||||
|
|
||||||
blackboxConfigMutable()->p_denom = 64; // 2kHz logging
|
blackboxConfigMutable()->p_ratio = 48; // 1.5kHz logging
|
||||||
|
blackboxInit();
|
||||||
|
EXPECT_EQ(256, blackboxIInterval);
|
||||||
|
EXPECT_EQ(5, blackboxPInterval);
|
||||||
|
EXPECT_EQ(5, blackboxGetRateDenom());
|
||||||
|
|
||||||
|
blackboxConfigMutable()->p_ratio = 64; // 2kHz logging
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
EXPECT_EQ(256, blackboxIInterval);
|
EXPECT_EQ(256, blackboxIInterval);
|
||||||
EXPECT_EQ(4, blackboxPInterval);
|
EXPECT_EQ(4, blackboxPInterval);
|
||||||
EXPECT_EQ(1, blackboxGetRateNum());
|
|
||||||
EXPECT_EQ(4, blackboxGetRateDenom());
|
EXPECT_EQ(4, blackboxGetRateDenom());
|
||||||
|
|
||||||
blackboxConfigMutable()->p_denom = 128; // 4kHz logging
|
blackboxConfigMutable()->p_ratio = 128; // 4kHz logging
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
EXPECT_EQ(256, blackboxIInterval);
|
EXPECT_EQ(256, blackboxIInterval);
|
||||||
EXPECT_EQ(2, blackboxPInterval);
|
EXPECT_EQ(2, blackboxPInterval);
|
||||||
EXPECT_EQ(1, blackboxGetRateNum());
|
|
||||||
EXPECT_EQ(2, blackboxGetRateDenom());
|
EXPECT_EQ(2, blackboxGetRateDenom());
|
||||||
|
|
||||||
blackboxConfigMutable()->p_denom = 256; // 8kHz logging
|
blackboxConfigMutable()->p_ratio = 256; // 8kHz logging
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
EXPECT_EQ(256, blackboxIInterval);
|
EXPECT_EQ(256, blackboxIInterval);
|
||||||
EXPECT_EQ(1, blackboxPInterval);
|
EXPECT_EQ(1, blackboxPInterval);
|
||||||
EXPECT_EQ(1, blackboxGetRateNum());
|
|
||||||
EXPECT_EQ(1, blackboxGetRateDenom());
|
EXPECT_EQ(1, blackboxGetRateDenom());
|
||||||
|
|
||||||
|
// 0.126 PIDloop
|
||||||
|
gyro.targetLooptime = 126;
|
||||||
|
blackboxConfigMutable()->p_ratio = 32; // 1kHz logging
|
||||||
|
blackboxInit();
|
||||||
|
EXPECT_EQ(253, blackboxIInterval);
|
||||||
|
EXPECT_EQ(7, blackboxPInterval);
|
||||||
|
EXPECT_EQ(7, blackboxGetRateDenom());
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue