Skip to content

Commit

Permalink
Add rosbag_snapshot to keep a buffer of recent messages in memory for…
Browse files Browse the repository at this point in the history
… saving to disk

Using `save_snapshot.sh` (or `rosrun rosbag_snapshot snapshot -t`), you can trigger it to save the current buffer to disk. This can be used to debug after an unexpected behavior occurs.

By default it is disabled.  It operates entirely independently of OM_ENABLE_RECORDING and OM_ENABLE_RECORDING_ALL.
  • Loading branch information
jeremysalwen committed Sep 15, 2024
1 parent 1d9fe79 commit c9d9927
Show file tree
Hide file tree
Showing 5 changed files with 53 additions and 7 deletions.
14 changes: 14 additions & 0 deletions config/mower_config.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -354,6 +354,20 @@
"description":"Set to true to record your session for debugging. Recordings will be stored in $HOME. Only enable for testing, otherwise your SD card will get full soon.",
"x-environment-variable":"OM_ENABLE_RECORDING_ALL"
},
"OM_SNAPSHOT_MEMORY_PER_TOPIC": {
"type": "number",
"default": 0.0,
"title": "Snapshot Buffer Memory per Topic",
"description": "Sets the maximum memory used per topic (in MB) by the Snapshot Buffer. The Snapshot Buffer stores a recent history of all messages sent, and can be dumped to disk using save_snapshot.sh. It is independent of OM_ENABLE_RECORDING",
"x-environment-variable": "OM_SNAPSHOT_MEMORY_PER_TOPIC"
},
"OM_SNAPSHOT_DURATION": {
"type": "number",
"default": 1200,
"title": "Snapshot Buffer ",
"description": "Sets the maximum age (in seconds) of messages to store in the Snapshot Buffer. The Snapshot Buffer stores a recent history of all messages sent, and can be dumped to disk using save_snapshot.sh. It is independent of OM_ENABLE_RECORDING",
"x-environment-variable": "OM_SNAPSHOT_DURATION"
},
"advanced":{
"type":"boolean",
"description":"Show advanced Mower Logic settings"
Expand Down
27 changes: 21 additions & 6 deletions config/mower_config.sh.example
Original file line number Diff line number Diff line change
Expand Up @@ -60,10 +60,6 @@ export OM_MOWER_ESC_TYPE="xesc_mini"
# Currently supported: ps3, steam_stick, steam_touch, xbox360
export OM_MOWER_GAMEPAD="xbox360"

# Set to true to record your session.
# Output will be stored in your $HOME
# export OM_ENABLE_RECORDING_ALL=False

# Full Sound Support - But read on carefully:
# Up to (and inclusive) OM hardware version 0.13.x, DFPlayer's power supply is set by default to 3.3V.
# This is done by solder jumper "JP1" whose board track is by default at 3.3V.
Expand Down Expand Up @@ -180,7 +176,7 @@ export OM_ENABLE_MOWER=true

# Set the automatic start value based on required behaviour
# 2 - AUTO - mow whenever possible
# 1 - SEMIAUTO - mow the entire map once then wait for manual start atgain
# 1 - SEMIAUTO - mow the entire map once then wait for manual start again
# 0 - MANUAL - mowing requires manual start (default if unset)
export OM_AUTOMATIC_MODE=0

Expand All @@ -189,7 +185,7 @@ export OM_OUTLINE_OFFSET=0.05
################################
## External MQTT Broker ##
################################
# Set thes in order to publish status data to your external MQTT broker.
# Set these in order to publish status data to your external MQTT broker.
# This is for use with smart home.

# export OM_MQTT_ENABLE=False
Expand All @@ -200,6 +196,25 @@ export OM_OUTLINE_OFFSET=0.05
# export OM_MQTT_TOPIC_PREFIX="openmower"


################################
## Debugging Settings ##
################################

# Set to true to record your session.
# Output will be stored in your $HOME
# export OM_ENABLE_RECORDING_ALL=False

# OM_SNAPSHOT options can be used to enable an in-memory buffer of all recent
# ROS messages for debugging. If something goes wrong, you can dump a
# a snapshot to disk to reconstruct what happened and debug further,
# using `$ ./utils/scripts/save_snapshot.sh output_file.bag`.
# Note that this mechanism is entirely separate from OM_ENABLE_RECORDING_*.

# Memory usage is measured in MB, and duration is measured in seconds.
# export OM_SNAPSHOT_MEMORY_PER_TOPIC=5.0
# export OM_SNAPSHOT_DURATION=1200


# source the default values for the hardware platform.
# you only need this line on non-docker installs. in the docker, it will be done automatically.
# source $(rospack find open_mower)/params/hardware_specific/$OM_MOWER/default_environment.sh
11 changes: 10 additions & 1 deletion src/open_mower/launch/include/_record.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<!--
Include this file to record all low level comms, so you can playback later on for debugging
Include this file to use these utilities to record all low level comms, so you can playback later on for debugging
-->
<launch>
<arg name="prefix" default="record"/>
Expand All @@ -22,4 +22,13 @@
<node if="$(optenv OM_ENABLE_RECORDING_ALL False)" pkg="rosbag" type="record" name="rosbag_record_diag_alle"
args="record -o /$(env HOME)/all_$(arg prefix) -a" />

<node name="snapshot" pkg="rosbag_snapshot" type="snapshot" args="" subst_value="true">
<rosparam>
default_duration_limit: $(optenv OM_SNAPSHOT_DURATION 1200) # Maximum time difference between newest and oldest message, seconds, overrides -d flag
default_memory_limit: $(optenv OM_SNAPSHOT_MEMORY_PER_TOPIC 0.0) # Maximum memory used by messages in each topic's buffer, MB, override -s flag
clear_buffer: false # No option / true will clear the buffer after writing to bag. False will not clear buffer
compression: LZ4 # LZ4, BZ2, uncompressed
record_all_topics: true
</rosparam>
</node>
</launch>
1 change: 1 addition & 0 deletions src/open_mower/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
<exec_depend>imu_filter_madgwick</exec_depend>
<exec_depend>twist_mux</exec_depend>
<exec_depend>rtcm_msgs</exec_depend>
<exec_depend>rosbag_snapshot</exec_depend>


<!-- The export tag contains other, unspecified, tags -->
Expand Down
7 changes: 7 additions & 0 deletions utils/scripts/save_snapshot.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
#!/bin/sh

# This script saves a record of all recent low-level ros messages to a ros bag.
# Usage: ./save_snapshot.sh output_file.bag


rosrun rosbag_snapshot snapshot -t -O "$1"

0 comments on commit c9d9927

Please sign in to comment.