forked from Archive/PX4-Autopilot
mavlink: Use round instead of ceil on BATTERY_STATUS percentage
Co-authored-by: Alex Mikhalev <alex@corvus-robotics.com>
This commit is contained in:
parent
1870b9245b
commit
d3b3de7159
|
@ -75,7 +75,7 @@ private:
|
|||
bat_msg.current_consumed = (battery_status.connected) ? battery_status.discharged_mah : -1;
|
||||
bat_msg.energy_consumed = -1;
|
||||
bat_msg.current_battery = (battery_status.connected) ? battery_status.current_filtered_a * 100 : -1;
|
||||
bat_msg.battery_remaining = (battery_status.connected) ? ceilf(battery_status.remaining * 100.f) : -1;
|
||||
bat_msg.battery_remaining = (battery_status.connected) ? roundf(battery_status.remaining * 100.f) : -1;
|
||||
// MAVLink extension: 0 is unsupported, in uORB it's NAN
|
||||
bat_msg.time_remaining = (battery_status.connected && (PX4_ISFINITE(battery_status.time_remaining_s))) ?
|
||||
math::max((int)battery_status.time_remaining_s, 1) : 0;
|
||||
|
|
Loading…
Reference in New Issue