Administrator
|
(Question from https://code.google.com/p/rtabmap/wiki/Tools moved here)
Hi Mathieu, Can you specify how can I record data in ROS for rtabmap. Which topics I should record to store into the rosbag and how to play it back using rtabmap. Should I run the rtabmap launch file when playing back the rosbag. Actually, I want to recreate the whole map that was built step by step as can be shown in the your video. Right now I am only getting the whole point cloud data (rtabmap.db). I would like to view the data for future processing since I do not have a screen on my pc which is attached to robot. Can you explain in steps. Thank you -Alex |
Administrator
|
Which video?
Note that the resulting database generated on your robot during the mapping session can be replayed directly at the rate of loop closure detection. This is what I've done to reproduce the IROS video after the actual mapping of the robot and taking the resulting "rtabmap.db" as input: You can open RTAB-Map (standalone, not the ros-pkg) using the configuration file above, then set "Source from database" and select the database above. Set Source rate to 2 Hz and press start, this should reproduce the video above. If you want to record at the rate of odometry (like for the Multi-session experiment), you can either record a rosbag or record a rtabmap database. You can take a look at these launch files: az3_bag_record.launch and az3_db_record.launch (the second uses data_recorder node), for rosbag and rtabmap database respectively. To replay them, respectively, look here for the rosbag example and here for the rtabmap example. Mathieu |
sorry for so late reply. This solved my problem of visualization. However, is there a way to do the same in rviz. My recorded bag files are way to large when recording the rtabmap (~10 GB) for a 5 minute run. I am not sure what might be the reason. I looked at your launch files for recording the rosbag but somehow it does not work for my system. What topics I should be recording when using rosbag for the openni2 topics to get the optimum results.
Thanks Alex
------
Alex
|
Administrator
|
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 /tfWhen 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 /tf3) 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 /odom4) 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 |
Free forum by Nabble | Edit this page |