mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-09 22:08:56 +08:00
refactor(battery_simulator): clean up param SIM_BAT_ENABLE (#26823)
* refactor(battery_simulator): remove SIM_BAT_ENABLE
disable instead with SIM_BAT_DRAIN <= 0
* fix(battery_simulator): disable battery sim only if SIM_BAT_DRAIN strictly < 0
* fix(battery_simulator): disable if 0, adjust limit to 0
* fix(battery_simulator): remove constraining again
now that SIM_BAT_DRAIN=0 means the module is not started we are safe
from division by zero again (param compare has a tolerance of 1e-7)
* fix(battery_simulator): constrain param to min of 1
to avoid division by zero.
This reverts commit 6380c4fdee.
* fix(battery_simulator): remove arbitrary param max
* fix(battery_simulator): reword long param description
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
* fix(battery_simulator): reword short param description
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
---------
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
This commit is contained in:
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
|
||||
@@ -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) {
|
||||
|
||||
@@ -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:
|
||||
|
||||
Reference in New Issue
Block a user