GCS_MAVLink: use get_battery_remaining_percentage() for BATTERY_STATUS

This commit is contained in:
Willian Galvani 2021-02-23 11:58:51 -03:00 committed by Jacob Walser
parent d583d157e7
commit ce312d0328
1 changed files with 1 additions and 1 deletions

View File

@ -233,7 +233,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),
get_battery_remaining_percentage(instance),
0, // time remaining, seconds (not provided)
MAV_BATTERY_CHARGE_STATE_UNDEFINED);
}