diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index cbaf724d9f2b..9c7c428ff837 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -249,7 +249,7 @@ fi load_mon start -if param compare SIM_BAT_ENABLE 1 +if param greater SIM_BAT_DRAIN 0 then battery_simulator start fi diff --git a/docs/en/simulation/failsafes.md b/docs/en/simulation/failsafes.md index 0087c8970dea..78d6357195f3 100644 --- a/docs/en/simulation/failsafes.md +++ b/docs/en/simulation/failsafes.md @@ -47,7 +47,7 @@ To control how fast the battery depletes to the minimal value use the parameter By changing [SIM_BAT_MIN_PCT](../advanced_config/parameter_reference.md#SIM_BAT_MIN_PCT) in flight, you can also test regaining capacity to simulate inaccurate battery state estimation or in-air charging technology. ::: -It is also possible to disable the simulated battery using [SIM_BAT_ENABLE](../advanced_config/parameter_reference.md#SIM_BAT_ENABLE) in order to, for example, provide an external battery simulation via MAVLink. +The simulated battery can be completely disabled by setting [SIM_BAT_DRAIN](../advanced_config/parameter_reference.md#SIM_BAT_DRAIN) to 0. This is useful, for example, if you provide an external battery simulation via MAVLink. ## Sensor/System Failure diff --git a/src/modules/simulation/battery_simulator/BatterySimulator.cpp b/src/modules/simulation/battery_simulator/BatterySimulator.cpp index 4f2957cfea51..36c9961bc14f 100644 --- a/src/modules/simulation/battery_simulator/BatterySimulator.cpp +++ b/src/modules/simulation/battery_simulator/BatterySimulator.cpp @@ -85,7 +85,8 @@ void BatterySimulator::Run() const hrt_abstime now_us = hrt_absolute_time(); - const float discharge_interval_us = _param_sim_bat_drain.get() * 1000 * 1000; + // Limit to +1.0 s to guard against division by 0 + const float discharge_interval_us = math::max(_param_sim_bat_drain.get(), 1.0f) * 1000 * 1000; if (_armed) { if (_last_integration_us != 0) { diff --git a/src/modules/simulation/battery_simulator/battery_simulator_params.yaml b/src/modules/simulation/battery_simulator/battery_simulator_params.yaml index 53830f027919..db3ac91ce8ec 100644 --- a/src/modules/simulation/battery_simulator/battery_simulator_params.yaml +++ b/src/modules/simulation/battery_simulator/battery_simulator_params.yaml @@ -2,22 +2,14 @@ module_name: battery_simulator parameters: - group: SITL definitions: - SIM_BAT_ENABLE: - description: - short: Simulator Battery enabled - long: |- - Enable or disable the internal battery simulation. This is useful - when the battery is simulated externally and interfaced with PX4 - through MAVLink for example. - type: boolean - default: 1 SIM_BAT_DRAIN: description: - short: Simulator Battery drain interval + short: Simulated battery full-discharge time + long: |- + Time in seconds for the simulated battery to drain from 100% to 0% while armed. Set to 0 to disable the battery simulator entirely (useful when battery state is provided externally, e.g. via MAVLink). type: float default: 60 - min: 1 - max: 86400 + min: 0 increment: 1 unit: s SIM_BAT_MIN_PCT: