From 5bb9babc206068e9ee67e1489433be94482a402f Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 1 Mar 2018 09:07:55 +0100 Subject: [PATCH] Mavlink: round battery percentage up instead of down --- src/modules/mavlink/mavlink_messages.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 67def31e0e..b3763f15df 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -553,7 +553,7 @@ protected: msg.load = cpuload.load * 1000.0f; msg.voltage_battery = (battery_status.connected) ? battery_status.voltage_filtered_v * 1000.0f : UINT16_MAX; msg.current_battery = (battery_status.connected) ? battery_status.current_filtered_a * 100.0f : -1; - msg.battery_remaining = (battery_status.connected) ? battery_status.remaining * 100.0f : -1; + msg.battery_remaining = (battery_status.connected) ? ceilf(battery_status.remaining * 100.0f) : -1; // TODO: fill in something useful in the fields below msg.drop_rate_comm = 0; msg.errors_comm = 0; @@ -572,7 +572,7 @@ protected: 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) ? battery_status.remaining * 100.0f : -1; + bat_msg.battery_remaining = (battery_status.connected) ? ceilf(battery_status.remaining * 100.0f) : -1; bat_msg.temperature = INT16_MAX; for (unsigned int i = 0; i < (sizeof(bat_msg.voltages) / sizeof(bat_msg.voltages[0])); i++) {