From 1e14b10dee8cae32818f74297dfb0b78086d4c21 Mon Sep 17 00:00:00 2001
From: Matthias Grob <maetugr@gmail.com>
Date: Sun, 13 Jan 2019 16:59:10 +0100
Subject: [PATCH] simulator_mavlink: take care of battery percentage rounding
 errors

In 5bb9babc206068e9ee67e1489433be94482a402f I made MAVLink send a
rounded up integer instead of rounded down. This makes sense in practice
because the low battery reactions happen exactly when the reported number
switches in the UI. But here we want to provoke an exact 50% in the UI so
we stop counting at 49.9%, it get's rounded up and we see the expected
result.
---
 src/modules/simulator/simulator_mavlink.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp
index 55ad7c001a..aadc006f42 100644
--- a/src/modules/simulator/simulator_mavlink.cpp
+++ b/src/modules/simulator/simulator_mavlink.cpp
@@ -327,7 +327,7 @@ void Simulator::handle_message(mavlink_message_t *msg, bool publish)
 				}
 
 				float ibatt = -1.0f; // no current sensor in simulation
-				const float minimum_percentage = 0.5f; // change this value if you want to simulate low battery reaction
+				const float minimum_percentage = 0.499f; // change this value if you want to simulate low battery reaction
 
 				/* Simulate the voltage of a linearly draining battery but stop at the minimum percentage */
 				float battery_percentage = 1.0f - (now_us - batt_sim_start) / discharge_interval_us;
-- 
GitLab