simulator_mavlink: switch battery max and min to fix simultion

In 3e6e1f5c2b 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.
This commit is contained in:
Matthias Grob 2019-01-13 16:52:04 +01:00
parent 766f911005
commit a89e550f3c
1 changed files with 2 additions and 2 deletions

View File

@ -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