Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

MAVLink Simulation: Battery Percentage Fix #11205

Merged
merged 2 commits into from
Jan 14, 2019
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions src/modules/simulator/simulator_mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -327,13 +327,13 @@ 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;

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