Posted by
matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/How-can-I-record-data-in-ROS-for-rtabmap-tp74p125.html
1) If you want to save some memory when recording a
rosbag at the cost of a decompression time on playing, you can record the compressed topics (don't forget the TF). For example:
$ rosbag record /camera/rgb/image_rect_color/compressed /camera/depth_registered/image_raw/compressedDepth /camera/depth_registered/camera_info /tf
When playing a rosbag with compressed image topics, you should set the "image_transport" parameter for each node subscribing to these topics (republish nodes can also be used as in the last example below):
<param name="rgb/image_transport" type="string" value="compressed"/>
<param name="depth/image_transport" type="string" value="compressedDepth"/>
2) However, the images are published at 30 Hz. RTAB-Map's odometry don't need images over 20 Hz, so we can use the
data_throttle nodelet to reduce the frame rate to 20 Hz (saving more memory):
$ rosrun nodelet nodelet standalone rtabmap_ros/data_throttle _max_rate:=20 rgb/image_in:=camera/rgb/image_rect_color depth/image_in:=camera/depth_registered/image_raw rgb/camera_info_in:=camera/depth_registered/camera_info rgb/image_out:=data_throttled_image depth/image_out:=data_throttled_image_depth rgb/camera_info_out:=data_throttled_camera_info
or
<launch>
<node pkg="nodelet" type="nodelet" name="data_throttle" args="standalone rtabmap_ros/data_throttle">
<param name="max_rate" type="double" value="20.0"/>
<remap from="rgb/image_in" to="camera/rgb/image_rect_color"/>
<remap from="depth/image_in" to="camera/depth_registered/image_raw"/>
<remap from="rgb/camera_info_in" to="camera/depth_registered/camera_info"/>
<remap from="rgb/image_out" to="data_throttled_image"/>
<remap from="depth/image_out" to="data_throttled_image_depth"/>
<remap from="rgb/camera_info_out" to="data_throttled_camera_info"/>
</node>
</launch>
$ rosbag record /data_throttled_image/compressed /data_throttled_image_depth/compressedDepth /data_throttled_camera_info /tf
3) If you don't use RTAB-Map's odometry node to feed
rtabmap with an odometry (e.g. you are using the robot odometry), you can record at a lowest rate since by default
rtabmap update rate is 1 Hz. Set 1 Hz above and record with odometry:
$ rosbag record /data_throttled_image/compressed /data_throttled_image_depth/compressedDepth /data_throttled_camera_info /tf /odom
4) To play the rosbag, here an example to re-use the default launch file like
rgbd_mapping_rviz.launch, just add these lines at the top of the launch file to remap/decompress topics to those set in the launch file:
<launch>
<param name="use_sim_time" type="bool" value="True"/>
<node name="camera_info_relay" type="relay" pkg="topic_tools" args="/data_throttled_camera_info /camera/depth_registered/camera_info"/>
<node name="republish_rgb" type="republish" pkg="image_transport" args="compressed in:=/data_throttled_image raw out:=/camera/rgb/image_rect_color" />
<node name="republish_depth" type="republish" pkg="image_transport" args="compressedDepth in:=/data_throttled_image_depth raw out:=/camera/depth_registered/image_raw" />
...
</launch>
$ rosbag play --clock recorded.bag