From a89e550f3cd4ed23618d28892a9a6b46ac1dc800 Mon Sep 17 00:00:00 2001 From: Matthias Grob <maetugr@gmail.com> Date: Sun, 13 Jan 2019 16:52:04 +0100 Subject: [PATCH] simulator_mavlink: switch battery max and min to fix simultion In 3e6e1f5c2b042accca72346273fc1755dd7670fa the simulated battery percentage was reversed. I'm assuming because of the possibly missleading variable name. Now I'm fixing it by switching the maximum and minimum voltage such that the name is not misleading anymore but it still works as expected. --- src/modules/simulator/simulator_mavlink.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 79d9a8a67f..55ad7c001a 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -332,8 +332,8 @@ void Simulator::handle_message(mavlink_message_t *msg, bool publish) /* 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; - battery_percentage = math::min(battery_percentage, minimum_percentage); - float vbatt = math::gradual(battery_percentage, 0.f, 1.f, _battery.full_cell_voltage(), _battery.empty_cell_voltage()); + battery_percentage = math::max(battery_percentage, minimum_percentage); + float vbatt = math::gradual(battery_percentage, 0.f, 1.f, _battery.empty_cell_voltage(), _battery.full_cell_voltage()); vbatt *= _battery.cell_count(); const float throttle = 0.0f; // simulate no throttle compensation to make the estimate predictable -- GitLab