GCS_MAVLink: update to use capacity_remaining_pct() as a bool

This commit is contained in:
Willian Galvani 2020-04-23 13:23:19 -03:00 committed by Andrew Tridgell
parent f7fa4b7c19
commit 018ff3d11c
1 changed files with 8 additions and 7 deletions

View File

@ -269,6 +269,9 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
} else {
consumed_wh = -1;
}
uint8_t _percentage = -1;
const int8_t percentage = battery.capacity_remaining_pct(_percentage, instance) ? _percentage : -1;
mavlink_msg_battery_status_send(chan,
instance, // id
MAV_BATTERY_FUNCTION_UNKNOWN, // function
@ -278,7 +281,7 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
current, // current in centiampere
consumed_mah, // total consumed current in milliampere.hour
consumed_wh, // consumed energy in hJ (hecto-Joules)
battery.capacity_remaining_pct(instance),
percentage,
0, // time remaining, seconds (not provided)
battery.get_mavlink_charge_state(instance), // battery charge state
cell_volts_ext, // Cell 11..14 voltages
@ -4639,14 +4642,13 @@ void GCS_MAVLINK::send_sys_status()
const AP_BattMonitor &battery = AP::battery();
float battery_current;
int8_t battery_remaining;
uint8_t battery_remaining = -1;
if (battery.healthy() && battery.current_amps(battery_current)) {
battery_remaining = battery.capacity_remaining_pct();
IGNORE_RETURN(battery.capacity_remaining_pct(battery_remaining));
battery_current = constrain_float(battery_current * 100,-INT16_MAX,INT16_MAX);
} else {
battery_current = -1;
battery_remaining = -1;
}
uint32_t control_sensors_present;
@ -5541,14 +5543,13 @@ void GCS_MAVLINK::send_high_latency() const
const AP_BattMonitor &battery = AP::battery();
float battery_current;
int8_t battery_remaining;
uint8_t battery_remaining = -1;
if (battery.healthy() && battery.current_amps(battery_current)) {
battery_remaining = battery.capacity_remaining_pct();
IGNORE_RETURN(battery.capacity_remaining_pct(battery_remaining));
battery_current = constrain_float(battery_current * 100,-INT16_MAX,INT16_MAX);
} else {
battery_current = -1;
battery_remaining = -1;
}
AP_Mission *mission = AP::mission();