Skip to content

Commit

Permalink
*_config.yaml: document usage of multiple batteries diagnostics
Browse files Browse the repository at this point in the history
  • Loading branch information
amilcarlucas committed Feb 21, 2022
1 parent e1d87f3 commit 866e807
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 4 deletions.
3 changes: 2 additions & 1 deletion mavros/launch/apm_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,8 @@ conn:

# sys_status
sys:
min_voltage: 10.0 # diagnostics min voltage
min_voltage: 10.0 # diagnostics min voltage, use a vector i.e. [16.2, 16.0] for multiple batteries, up-to 10 are supported
# to achieve the same on a ROS launch file do: <rosparam param="sys/min_voltage">[16.2, 16.0]</rosparam>
disable_diag: false # disable all sys_status diagnostics, except heartbeat

# sys_time
Expand Down
7 changes: 4 additions & 3 deletions mavros/launch/px4_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,14 +7,15 @@ startup_px4_usb_quirk: false

# sys_status & sys_time connection options
conn:
heartbeat_rate: 1.0 # send hertbeat rate in Hertz
timeout: 10.0 # hertbeat timeout in seconds
heartbeat_rate: 1.0 # send heartbeat rate in Hertz
timeout: 10.0 # heartbeat timeout in seconds
timesync_rate: 10.0 # TIMESYNC rate in Hertz (feature disabled if 0.0)
system_time_rate: 1.0 # send system time to FCU rate in Hertz (disabled if 0.0)

# sys_status
sys:
min_voltage: 10.0 # diagnostics min voltage
min_voltage: 10.0 # diagnostics min voltage, use a vector i.e. [16.2, 16.0] for multiple batteries, up-to 10 are supported
# to achieve the same on a ROS launch file do: <rosparam param="sys/min_voltage">[16.2, 16.0]</rosparam>
disable_diag: false # disable all sys_status diagnostics, except heartbeat

# sys_time
Expand Down

0 comments on commit 866e807

Please sign in to comment.