mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-18 22:05:17 +03:00
Increased vbat precision
This commit is contained in:
parent
24344405fb
commit
9d5fb85474
30 changed files with 124 additions and 120 deletions
|
@ -116,7 +116,7 @@ void setDefaultSimulationState()
|
|||
|
||||
simulationBatteryState = BATTERY_OK;
|
||||
simulationBatteryCellCount = 4;
|
||||
simulationBatteryVoltage = 168;
|
||||
simulationBatteryVoltage = 1680;
|
||||
simulationBatteryAmperage = 0;
|
||||
simulationMahDrawn = 0;
|
||||
simulationAltitude = 0;
|
||||
|
@ -203,8 +203,8 @@ TEST(OsdTest, TestInit)
|
|||
|
||||
// and
|
||||
// this battery configuration (used for battery voltage elements)
|
||||
batteryConfigMutable()->vbatmincellvoltage = 33;
|
||||
batteryConfigMutable()->vbatmaxcellvoltage = 43;
|
||||
batteryConfigMutable()->vbatmincellvoltage = 330;
|
||||
batteryConfigMutable()->vbatmaxcellvoltage = 430;
|
||||
|
||||
// when
|
||||
// OSD is initialised
|
||||
|
@ -361,7 +361,7 @@ TEST(OsdTest, TestStatsImperial)
|
|||
gpsSol.groundSpeed = 500;
|
||||
GPS_distanceToHome = 20;
|
||||
GPS_distanceFlownInCm = 2000;
|
||||
simulationBatteryVoltage = 158;
|
||||
simulationBatteryVoltage = 1580;
|
||||
simulationAltitude = 100;
|
||||
simulationTime += 1e6;
|
||||
osdRefresh(simulationTime);
|
||||
|
@ -370,7 +370,7 @@ TEST(OsdTest, TestStatsImperial)
|
|||
gpsSol.groundSpeed = 800;
|
||||
GPS_distanceToHome = 50;
|
||||
GPS_distanceFlownInCm = 10000;
|
||||
simulationBatteryVoltage = 147;
|
||||
simulationBatteryVoltage = 1470;
|
||||
simulationAltitude = 150;
|
||||
simulationTime += 1e6;
|
||||
osdRefresh(simulationTime);
|
||||
|
@ -379,7 +379,7 @@ TEST(OsdTest, TestStatsImperial)
|
|||
gpsSol.groundSpeed = 200;
|
||||
GPS_distanceToHome = 100;
|
||||
GPS_distanceFlownInCm = 20000;
|
||||
simulationBatteryVoltage = 152;
|
||||
simulationBatteryVoltage = 1520;
|
||||
simulationAltitude = 200;
|
||||
simulationTime += 1e6;
|
||||
osdRefresh(simulationTime);
|
||||
|
@ -396,8 +396,8 @@ TEST(OsdTest, TestStatsImperial)
|
|||
displayPortTestBufferSubstring(2, row++, "LAST ARM : 00:03");
|
||||
displayPortTestBufferSubstring(2, row++, "MAX SPEED : 17");
|
||||
displayPortTestBufferSubstring(2, row++, "MAX DISTANCE : 328%c", SYM_FT);
|
||||
displayPortTestBufferSubstring(2, row++, "MIN BATTERY : 14.7%c", SYM_VOLT);
|
||||
displayPortTestBufferSubstring(2, row++, "END BATTERY : 15.2%c", SYM_VOLT);
|
||||
displayPortTestBufferSubstring(2, row++, "MIN BATTERY : 14.70%c", SYM_VOLT);
|
||||
displayPortTestBufferSubstring(2, row++, "END BATTERY : 15.20%c", SYM_VOLT);
|
||||
displayPortTestBufferSubstring(2, row++, "MIN RSSI : 25%%");
|
||||
displayPortTestBufferSubstring(2, row++, "MAX ALTITUDE : 6.5%c", SYM_FT);
|
||||
displayPortTestBufferSubstring(2, row++, "FLIGHT DISTANCE : 656%c", SYM_FT);
|
||||
|
@ -427,13 +427,13 @@ TEST(OsdTest, TestStatsMetric)
|
|||
gpsSol.groundSpeed = 800;
|
||||
GPS_distanceToHome = 100;
|
||||
GPS_distanceFlownInCm = 10000;
|
||||
simulationBatteryVoltage = 147;
|
||||
simulationBatteryVoltage = 1470;
|
||||
simulationAltitude = 200;
|
||||
simulationTime += 1e6;
|
||||
osdRefresh(simulationTime);
|
||||
osdRefresh(simulationTime);
|
||||
|
||||
simulationBatteryVoltage = 152;
|
||||
simulationBatteryVoltage = 1520;
|
||||
simulationTime += 1e6;
|
||||
osdRefresh(simulationTime);
|
||||
|
||||
|
@ -449,8 +449,8 @@ TEST(OsdTest, TestStatsMetric)
|
|||
displayPortTestBufferSubstring(2, row++, "LAST ARM : 00:02");
|
||||
displayPortTestBufferSubstring(2, row++, "MAX SPEED : 28");
|
||||
displayPortTestBufferSubstring(2, row++, "MAX DISTANCE : 100%c", SYM_M);
|
||||
displayPortTestBufferSubstring(2, row++, "MIN BATTERY : 14.7%c", SYM_VOLT);
|
||||
displayPortTestBufferSubstring(2, row++, "END BATTERY : 15.2%c", SYM_VOLT);
|
||||
displayPortTestBufferSubstring(2, row++, "MIN BATTERY : 14.70%c", SYM_VOLT);
|
||||
displayPortTestBufferSubstring(2, row++, "END BATTERY : 15.20%c", SYM_VOLT);
|
||||
displayPortTestBufferSubstring(2, row++, "MIN RSSI : 25%%");
|
||||
displayPortTestBufferSubstring(2, row++, "MAX ALTITUDE : 2.0%c", SYM_M);
|
||||
displayPortTestBufferSubstring(2, row++, "FLIGHT DISTANCE : 100%c", SYM_M);
|
||||
|
@ -513,7 +513,7 @@ TEST(OsdTest, TestAlarms)
|
|||
printf("%d\n", i);
|
||||
#endif
|
||||
displayPortTestBufferSubstring(8, 1, "%c99", SYM_RSSI);
|
||||
displayPortTestBufferSubstring(12, 1, "%c16.8%c", SYM_BATT_FULL, SYM_VOLT);
|
||||
displayPortTestBufferSubstring(12, 1, "%c16.80%c", SYM_BATT_FULL, SYM_VOLT);
|
||||
displayPortTestBufferSubstring(1, 1, "%c00:", SYM_FLY_M); // only test the minute part of the timer
|
||||
displayPortTestBufferSubstring(20, 1, "%c01:", SYM_ON_M); // only test the minute part of the timer
|
||||
displayPortTestBufferSubstring(23, 7, " .0%c", SYM_M);
|
||||
|
@ -523,7 +523,7 @@ TEST(OsdTest, TestAlarms)
|
|||
// all values are out of range
|
||||
rssi = 128;
|
||||
simulationBatteryState = BATTERY_CRITICAL;
|
||||
simulationBatteryVoltage = 135;
|
||||
simulationBatteryVoltage = 1350;
|
||||
simulationAltitude = 12000;
|
||||
simulationTime += 60e6;
|
||||
osdRefresh(simulationTime);
|
||||
|
@ -542,7 +542,7 @@ TEST(OsdTest, TestAlarms)
|
|||
#endif
|
||||
if (i % 2 == 0) {
|
||||
displayPortTestBufferSubstring(8, 1, "%c12", SYM_RSSI);
|
||||
displayPortTestBufferSubstring(12, 1, "%c13.5%c", SYM_MAIN_BATT, SYM_VOLT);
|
||||
displayPortTestBufferSubstring(12, 1, "%c13.50%c", SYM_MAIN_BATT, SYM_VOLT);
|
||||
displayPortTestBufferSubstring(1, 1, "%c01:", SYM_FLY_M); // only test the minute part of the timer
|
||||
displayPortTestBufferSubstring(20, 1, "%c02:", SYM_ON_M); // only test the minute part of the timer
|
||||
displayPortTestBufferSubstring(23, 7, " 120.0%c", SYM_M);
|
||||
|
@ -677,7 +677,7 @@ TEST(OsdTest, TestElementPower)
|
|||
osdConfigMutable()->item_pos[OSD_POWER] = OSD_POS(1, 10) | OSD_PROFILE_1_FLAG;
|
||||
|
||||
// and
|
||||
simulationBatteryVoltage = 100; // 10V
|
||||
simulationBatteryVoltage = 1000; // 10V
|
||||
|
||||
// and
|
||||
simulationBatteryAmperage = 0; // 0A
|
||||
|
@ -837,7 +837,7 @@ TEST(OsdTest, TestElementWarningsBattery)
|
|||
osdWarnSetState(OSD_WARNING_BATTERY_NOT_FULL, true);
|
||||
|
||||
// and
|
||||
batteryConfigMutable()->vbatfullcellvoltage = 41;
|
||||
batteryConfigMutable()->vbatfullcellvoltage = 410;
|
||||
|
||||
// and
|
||||
// 4S battery
|
||||
|
@ -845,7 +845,7 @@ TEST(OsdTest, TestElementWarningsBattery)
|
|||
|
||||
// and
|
||||
// full battery
|
||||
simulationBatteryVoltage = 168;
|
||||
simulationBatteryVoltage = 1680;
|
||||
simulationBatteryState = BATTERY_OK;
|
||||
|
||||
// when
|
||||
|
@ -857,7 +857,7 @@ TEST(OsdTest, TestElementWarningsBattery)
|
|||
|
||||
// given
|
||||
// low battery
|
||||
simulationBatteryVoltage = 140;
|
||||
simulationBatteryVoltage = 1400;
|
||||
simulationBatteryState = BATTERY_WARNING;
|
||||
|
||||
// when
|
||||
|
@ -868,8 +868,8 @@ TEST(OsdTest, TestElementWarningsBattery)
|
|||
displayPortTestBufferSubstring(9, 10, "LOW BATTERY ");
|
||||
|
||||
// given
|
||||
// crtical battery
|
||||
simulationBatteryVoltage = 132;
|
||||
// critical battery
|
||||
simulationBatteryVoltage = 1320;
|
||||
simulationBatteryState = BATTERY_CRITICAL;
|
||||
|
||||
// when
|
||||
|
@ -881,7 +881,7 @@ TEST(OsdTest, TestElementWarningsBattery)
|
|||
|
||||
// given
|
||||
// used battery
|
||||
simulationBatteryVoltage = ((batteryConfig()->vbatmaxcellvoltage - 2) * simulationBatteryCellCount) - 1;
|
||||
simulationBatteryVoltage = ((batteryConfig()->vbatmaxcellvoltage - 20) * simulationBatteryCellCount) - 1;
|
||||
simulationBatteryState = BATTERY_OK;
|
||||
|
||||
// when
|
||||
|
@ -893,7 +893,7 @@ TEST(OsdTest, TestElementWarningsBattery)
|
|||
|
||||
// given
|
||||
// full battery
|
||||
simulationBatteryVoltage = ((batteryConfig()->vbatmaxcellvoltage - 2) * simulationBatteryCellCount);
|
||||
simulationBatteryVoltage = ((batteryConfig()->vbatmaxcellvoltage - 20) * simulationBatteryCellCount);
|
||||
simulationBatteryState = BATTERY_OK;
|
||||
|
||||
// when
|
||||
|
|
|
@ -164,7 +164,7 @@ TEST(TelemetryCrsfTest, TestBattery)
|
|||
EXPECT_EQ(67, remaining);
|
||||
EXPECT_EQ(crfsCrc(frame, frameLen), frame[11]);
|
||||
|
||||
testBatteryVoltage = 33; // 3.3V = 3300 mv
|
||||
testBatteryVoltage = 330; // 3.3V = 3300 mv
|
||||
testAmperage = 2960; // = 29.60A = 29600mA - amperage is in 0.01A steps
|
||||
testmAhDrawn = 1234;
|
||||
frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_BATTERY_SENSOR);
|
||||
|
|
|
@ -62,7 +62,7 @@ int16_t gyroGetTemperature(void) {
|
|||
return gyroTemperature;
|
||||
}
|
||||
|
||||
static uint16_t vbat = 100;
|
||||
static uint16_t vbat = 1000;
|
||||
uint16_t getVbat(void)
|
||||
{
|
||||
return vbat;
|
||||
|
@ -128,7 +128,7 @@ typedef struct serialPortStub_s {
|
|||
} serialPortStub_t;
|
||||
|
||||
|
||||
static uint16_t testBatteryVoltage = 100;
|
||||
static uint16_t testBatteryVoltage = 1000;
|
||||
uint16_t getBatteryVoltage(void)
|
||||
{
|
||||
return testBatteryVoltage;
|
||||
|
@ -469,13 +469,13 @@ TEST_F(IbusTelemteryProtocolUnitTest, Test_IbusRespondToGetMeasurementVbattCellV
|
|||
//Given ibus command: Sensor at address 1, please send your measurement
|
||||
//then we respond with: I'm reading 0.1 volts
|
||||
testBatteryCellCount =3;
|
||||
testBatteryVoltage = 30;
|
||||
testBatteryVoltage = 300;
|
||||
checkResponseToCommand("\x04\xA1\x5a\xff", 4, "\x06\xA1\x64\x00\xf4\xFe", 6);
|
||||
|
||||
//Given ibus command: Sensor at address 1, please send your measurement
|
||||
//then we respond with: I'm reading 0.1 volts
|
||||
testBatteryCellCount =1;
|
||||
testBatteryVoltage = 10;
|
||||
testBatteryVoltage = 100;
|
||||
checkResponseToCommand("\x04\xA1\x5a\xff", 4, "\x06\xA1\x64\x00\xf4\xFe", 6);
|
||||
}
|
||||
|
||||
|
@ -486,13 +486,13 @@ TEST_F(IbusTelemteryProtocolUnitTest, Test_IbusRespondToGetMeasurementVbattPackV
|
|||
//Given ibus command: Sensor at address 1, please send your measurement
|
||||
//then we respond with: I'm reading 0.1 volts
|
||||
testBatteryCellCount =3;
|
||||
testBatteryVoltage = 10;
|
||||
testBatteryVoltage = 100;
|
||||
checkResponseToCommand("\x04\xA1\x5a\xff", 4, "\x06\xA1\x64\x00\xf4\xFe", 6);
|
||||
|
||||
//Given ibus command: Sensor at address 1, please send your measurement
|
||||
//then we respond with: I'm reading 0.1 volts
|
||||
testBatteryCellCount =1;
|
||||
testBatteryVoltage = 10;
|
||||
testBatteryVoltage = 100;
|
||||
checkResponseToCommand("\x04\xA1\x5a\xff", 4, "\x06\xA1\x64\x00\xf4\xFe", 6);
|
||||
}
|
||||
|
||||
|
@ -580,7 +580,7 @@ TEST_F(IbusTelemteryProtocolUnitTestDaisyChained, Test_IbusRespondToGetMeasureme
|
|||
//Given ibus command: Sensor at address 3, please send your measurement
|
||||
//then we respond with: I'm reading 0.1 volts
|
||||
testBatteryCellCount = 1;
|
||||
testBatteryVoltage = 10;
|
||||
testBatteryVoltage = 100;
|
||||
checkResponseToCommand("\x04\xA3\x58\xff", 4, "\x06\xA3\x64\x00\xf2\xfe", 6);
|
||||
|
||||
//Given ibus command: Sensor at address 4, please send your measurement
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue