Browse Source

GCS_MAVLink: Provide the time remaining

gps-1.3.1
李孟晓 3 years ago committed by Andrew Tridgell
parent
commit
54b68ffae3
  1. 6
      libraries/GCS_MAVLink/GCS_Common.cpp

6
libraries/GCS_MAVLink/GCS_Common.cpp

@ -280,6 +280,10 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const @@ -280,6 +280,10 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
} else {
consumed_wh = -1;
}
uint32_t time_remaining;
if (!battery.time_remaining(time_remaining, instance)) {
time_remaining = 0;
}
mavlink_msg_battery_status_send(chan,
instance, // id
@ -291,7 +295,7 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const @@ -291,7 +295,7 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
consumed_mah, // total consumed current in milliampere.hour
consumed_wh, // consumed energy in hJ (hecto-Joules)
percentage,
0, // time remaining, seconds (not provided)
time_remaining, // time remaining, seconds
battery.get_mavlink_charge_state(instance), // battery charge state
cell_volts_ext, // Cell 11..14 voltages
0, // battery mode

Loading…
Cancel
Save