π― Problem
The rosbag recorder in docker-compose.yml uses ros2 bag record -a which records all topics. This causes the recorded bag size to explode, especially when Nav2 is running.
Current command (docker-compose.yml L306):
ros2 bag record -a -o /workspace/rosbags/recording_$(date +%Y%m%d_%H%M%S) --exclude-topics /front_stereo_camera/left/image_raw
Only the raw camera image is excluded. All other high-bandwidth topics are still recorded.
π High-Bandwidth Topics Being Recorded
When Nav2 is running, the following topics publish at high frequency and/or large message sizes:
| Topic |
Type |
Why it's large |
/front_3d_lidar/lidar_points |
sensor_msgs/PointCloud2 |
3D LiDAR point cloud β very large per message |
/local_costmap/costmap |
nav_msgs/OccupancyGrid |
Updated at controller frequency (~20 Hz) |
/global_costmap/costmap |
nav_msgs/OccupancyGrid |
Full map-sized grid, updated periodically |
/map |
nav_msgs/OccupancyGrid |
Static map (large, but infrequent) |
/front_stereo_camera/left/image_raw/compressed |
sensor_msgs/CompressedImage |
The republished compressed image is still recorded |
/tf |
tf2_msgs/TFMessage |
High frequency transform updates |
| Nav2 internal topics |
Various |
/local_costmap/costmap_raw, /global_costmap/costmap_raw, planner internals, etc. |
π‘ Proposed Fix
Switch from record -a (all topics) to explicitly listing only the topics needed for data collection and evaluation:
ros2 bag record \
/chassis/odom \
/cmd_vel \
/front_stereo_camera/left/image_raw/compressed \
/joy \
/tf \
/tf_static \
/start_marker \
/goal_marker \
/plan \
/goal_pose \
-o /workspace/rosbags/recording_$(date +%Y%m%d_%H%M%S)
Alternatively, use --exclude-regex to drop the known heavy topics:
ros2 bag record -a \
--exclude-regex '.*costmap.*|.*lidar_points.*|.*image_raw$|.*bond.*|.*parameter_events.*' \
-o /workspace/rosbags/recording_$(date +%Y%m%d_%H%M%S)
π References
- File:
docker-compose.yml L290-307
- Data processing config:
costnav_isaacsim/il_baselines/data_processing/configs/processing_config.yaml (only uses /front_stereo_camera/left/image_raw)
π― Problem
The rosbag recorder in
docker-compose.ymlusesros2 bag record -awhich records all topics. This causes the recorded bag size to explode, especially when Nav2 is running.Current command (
docker-compose.ymlL306):ros2 bag record -a -o /workspace/rosbags/recording_$(date +%Y%m%d_%H%M%S) --exclude-topics /front_stereo_camera/left/image_rawOnly the raw camera image is excluded. All other high-bandwidth topics are still recorded.
π High-Bandwidth Topics Being Recorded
When Nav2 is running, the following topics publish at high frequency and/or large message sizes:
/front_3d_lidar/lidar_pointssensor_msgs/PointCloud2/local_costmap/costmapnav_msgs/OccupancyGrid/global_costmap/costmapnav_msgs/OccupancyGrid/mapnav_msgs/OccupancyGrid/front_stereo_camera/left/image_raw/compressedsensor_msgs/CompressedImage/tftf2_msgs/TFMessage/local_costmap/costmap_raw,/global_costmap/costmap_raw, planner internals, etc.π‘ Proposed Fix
Switch from
record -a(all topics) to explicitly listing only the topics needed for data collection and evaluation:ros2 bag record \ /chassis/odom \ /cmd_vel \ /front_stereo_camera/left/image_raw/compressed \ /joy \ /tf \ /tf_static \ /start_marker \ /goal_marker \ /plan \ /goal_pose \ -o /workspace/rosbags/recording_$(date +%Y%m%d_%H%M%S)Alternatively, use
--exclude-regexto drop the known heavy topics:π References
docker-compose.ymlL290-307costnav_isaacsim/il_baselines/data_processing/configs/processing_config.yaml(only uses/front_stereo_camera/left/image_raw)