mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: fixed initial reporting of battery remaining
we were not showing battery remaining 100% until we used some battery
This commit is contained in:
parent
e80d73df93
commit
ed20c4cbc8
@ -447,6 +447,8 @@ static struct {
|
|||||||
float current_total_mah;
|
float current_total_mah;
|
||||||
// true when a low battery event has happened
|
// true when a low battery event has happened
|
||||||
bool low_batttery;
|
bool low_batttery;
|
||||||
|
// time when current was last read
|
||||||
|
uint32_t last_time_ms;
|
||||||
} battery;
|
} battery;
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -216,10 +216,10 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
|
|||||||
uint16_t battery_current = -1;
|
uint16_t battery_current = -1;
|
||||||
uint8_t battery_remaining = -1;
|
uint8_t battery_remaining = -1;
|
||||||
|
|
||||||
if (battery.current_total_mah != 0 && g.pack_capacity != 0) {
|
if (battery.last_time_ms != 0) {
|
||||||
battery_remaining = (100.0 * (g.pack_capacity - battery.current_total_mah) / g.pack_capacity);
|
if (g.pack_capacity != 0) {
|
||||||
}
|
battery_remaining = (100.0 * (g.pack_capacity - battery.current_total_mah) / g.pack_capacity);
|
||||||
if (battery.current_total_mah != 0) {
|
}
|
||||||
battery_current = battery.current_amps * 100;
|
battery_current = battery.current_amps * 100;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -52,17 +52,16 @@ static void read_battery(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (g.battery_monitoring == 4) {
|
if (g.battery_monitoring == 4) {
|
||||||
static uint32_t last_time_ms;
|
|
||||||
uint32_t tnow = hal.scheduler->millis();
|
uint32_t tnow = hal.scheduler->millis();
|
||||||
float dt = tnow - last_time_ms;
|
float dt = tnow - battery.last_time_ms;
|
||||||
if (last_time_ms != 0 && dt < 2000) {
|
// this copes with changing the pin at runtime
|
||||||
// this copes with changing the pin at runtime
|
batt_curr_pin->set_pin(g.battery_curr_pin);
|
||||||
batt_curr_pin->set_pin(g.battery_curr_pin);
|
battery.current_amps = CURRENT_AMPS(batt_curr_pin);
|
||||||
battery.current_amps = CURRENT_AMPS(batt_curr_pin);
|
if (battery.last_time_ms != 0 && dt < 2000) {
|
||||||
// .0002778 is 1/3600 (conversion to hours)
|
// .0002778 is 1/3600 (conversion to hours)
|
||||||
battery.current_total_mah += battery.current_amps * dt * 0.0002778f;
|
battery.current_total_mah += battery.current_amps * dt * 0.0002778f;
|
||||||
}
|
}
|
||||||
last_time_ms = tnow;
|
battery.last_time_ms = tnow;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (battery.voltage != 0 &&
|
if (battery.voltage != 0 &&
|
||||||
|
Loading…
Reference in New Issue
Block a user