diff --git a/src/modules/simulator/simulator.h b/src/modules/simulator/simulator.h index da8b5708ca..6f940f83de 100644 --- a/src/modules/simulator/simulator.h +++ b/src/modules/simulator/simulator.h @@ -286,7 +286,7 @@ private: DEFINE_PARAMETERS( (ParamFloat) _param_sim_bat_drain, ///< battery drain interval - (ParamFloat) _battery_min_percentage, //< minimum battery percentage + (ParamFloat) _param_bat_min_pct, //< minimum battery percentage (ParamFloat) _param_sim_gps_noise_x, (ParamBool) _param_sim_gps_block, (ParamBool) _param_sim_accel_block, diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 0922caaf30..e979c150bf 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -369,7 +369,7 @@ void Simulator::handle_message_hil_sensor(const mavlink_message_t *msg) float ibatt = -1.0f; // no current sensor in simulation - battery_percentage = math::max(battery_percentage, _battery_min_percentage.get() / 100.f); + battery_percentage = math::max(battery_percentage, _param_bat_min_pct.get() / 100.f); float vbatt = math::gradual(battery_percentage, 0.f, 1.f, _battery.empty_cell_voltage(), _battery.full_cell_voltage()); vbatt *= _battery.cell_count();