Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d-posix/rcS
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion docs/en/simulation/failsafes.md
Original file line number Diff line number Diff line change
Expand Up @@ -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 -1. This is useful, for example, if you provide an external battery simulation via MAVLink.

## Sensor/System Failure

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,21 +2,15 @@ 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
long: |-
Set <= 0 to entirely disable the battery simulator.
This is useful when the battery is simulated externally and interfaced with PX4, for example through MAVLink.
type: float
default: 60
min: 1
min: -1
max: 86400
increment: 1
unit: s
Expand Down
Loading