Skip to content

Commit

Permalink
simulator_mavlink: switch battery max and min to fix simultion
Browse files Browse the repository at this point in the history
In 3e6e1f5 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.
  • Loading branch information
MaEtUgR committed Jan 14, 2019
1 parent 766f911 commit a89e550
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions src/modules/simulator/simulator_mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit a89e550

Please sign in to comment.