GCS_Mavlink: constrain battery current to avoid wrap

This commit is contained in:
Peter Hall 2020-02-11 17:03:38 +00:00 committed by Peter Barker
parent 2bd6d4674b
commit b1742b4e19

View File

@ -217,7 +217,7 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
float current, consumed_mah, consumed_wh;
if (battery.current_amps(current, instance)) {
current *= 100;
current = constrain_float(current * 100,-INT16_MAX,INT16_MAX);
} else {
current = -1;
}
@ -2031,7 +2031,7 @@ void GCS_MAVLINK::send_battery2()
if (battery.num_instances() > 1) {
float current;
if (battery.current_amps(current, 1)) {
current *= 100; // 10*mA
current = constrain_float(current * 100,-INT16_MAX,INT16_MAX); // 10*mA
} else {
current = -1;
}
@ -4167,7 +4167,7 @@ void GCS_MAVLINK::send_sys_status()
if (battery.healthy() && battery.current_amps(battery_current)) {
battery_remaining = battery.capacity_remaining_pct();
battery_current *= 100;
battery_current = constrain_float(battery_current * 100,-INT16_MAX,INT16_MAX);
} else {
battery_current = -1;
battery_remaining = -1;