fix(battery_simulator): disable if 0, adjust limit to 0

This commit is contained in:
Balduin 2026-04-08 08:54:58 +02:00
parent e29e69f36b
commit da9d8342db
3 changed files with 4 additions and 4 deletions

View File

@ -249,7 +249,7 @@ fi
load_mon start
if param greater SIM_BAT_DRAIN 0 || param compare SIM_BAT_DRAIN 0
if param greater SIM_BAT_DRAIN 0
then
battery_simulator start
fi

View File

@ -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.
:::
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.
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

View File

@ -6,11 +6,11 @@ parameters:
description:
short: Simulator Battery drain interval
long: |-
Set to -1 to entirely disable the battery simulator.
Set to 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: 0
max: 86400
increment: 1
unit: s