Skip to content

Commit

Permalink
simulator_mavlink: take care of battery percentage rounding errors
Browse files Browse the repository at this point in the history
In 5bb9bab 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.
  • Loading branch information
MaEtUgR committed Jan 13, 2019
1 parent b84e01b commit d3a0311
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion src/modules/simulator/simulator_mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit d3a0311

Please sign in to comment.