Dear Mathieu,
I have finished the tutorial from the RTABMAP multi-session mapping using the standalone rtabmap. I want to create something similar to that tutorial using ROS and rtabmap on my robot platform. I am so far able to produce nice maps, but due to limitation on the memory, I would like to try large scale mapping(eg. mapping the entire ground floor of a buildiing). My system consists of a robot platform with a URG hokuyo senor and xtion pro live sensor. I get fairly good odometry from my robot. I am using ROS hydro. My questions are: 1) From the video, there are 5 databases that are run one after the other once each one finishes mapping. To do that, do I need to save each database by killing rtabmap launch so that it stores the rtabmap.db in default .ros/rtabmap.db, then, save this file to some place as map1. And then, continue mapping by repeating this process of killing the node and saving. Can you provide details on how you created the databases? 2) From the multi-session mapping tutorial, I see that when the second database is selected the process starts with a new origin and the previous data vanishes. As rtabmap finds the earlier visited areas that part of the visited map is added to the present map, am I correct on this part? How does the trajectory adjusts, as i can see from the final graph map the graph nodes and trajectory is smooth with just one origin? How do rtabmap deals with multiple graph trajectories to generate a single smooth trajectory with edges and vertices? 4) If I remove "delete_db_on_start" from the launch file, will the rtabmap continue to map from the previous mapping session? How is this method different from the multi-session mapping apart from it will create a single database? 5) Also, when viewing the process in rviz, how do I visualize the graph nodes with edges and vertices as can be seen in the standalone rtabmapviz? Sorry for too many questions. Thank you Alex
------
Alex
|
Administrator
|
Hi Alex,
1) We made multiple databases for convenience, we could have created only one. The databases were created from these 5 ROS bags (RGBD images are recorded at 10Hz using data_throttle). Between the recording of each ROS bag, the robot controller is restarted to reinitialize the odometry (giving the identity pose for the first image). When RTAB-Map detects an Identity pose, it automatically creates a new map. Here the command used to record the ROS bags on our robot (images are saved compressed to save space): <!-- Throttling OpenNI messages (using nodelet manager of OpenNI)--> <group ns="camera"> <node pkg="nodelet" type="nodelet" name="data_throttle" args="load rtabmap_ros/data_throttle camera_nodelet_manager"> <param name="rate" type="double" value="10.0"/> <remap from="rgb/image_in" to="rgb/image_rect_color"/> <remap from="depth/image_in" to="depth_registered/image_raw"/> <remap from="rgb/camera_info_in" to="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> </group> $ rosbag record camera/data_throttled_image/compressed camera/data_throttled_image_depth/compressedDepth camera/data_throttled_camera_info tf base_scan /base_controller/odomIf you want to convert the ROS bags to RTAB-Map database format using data_recorder, you can play them while having the data_recorder launched like this (so they can be played in the standalone version like in the multi-session tutorial): <node name="data_recorder" pkg="rtabmap_ros" type="data_recorder"> <param name="output_file_name" value="output_record.db" type="string"/> <param name="frame_id" type="string" value="base_footprint"/> <param name="subscribe_odometry" type="bool" value="true"/> <param name="subscribe_depth" type="bool" value="true"/> <param name="subscribe_laserScan" type="bool" value="true"/> <remap from="odom" to="/base_controller/odom"/> <remap from="scan" to="/base_scan"/> <remap from="rgb/image" to="camera/data_throttled_image"/> <remap from="depth/image" to="camera/data_throttled_image_depth"/> <remap from="rgb/camera_info" to="camera/data_throttled_camera_info"/> <param name="rgb/image_transport" type="string" value="compressed"/> <param name="depth/image_transport" type="string" value="compressedDepth"/> <param name="queue_size" type="int" value="10"/> </node> 2) Which referential is taken is defined by "RGBD/OptimizeFromGraphEnd" parameter: "Optimize the graph from the newest node. If false, the graph is optimized from the oldest node of the current graph (this adds an overhead computation to detect to oldest node of the current graph, but it can be useful to preserve the map referential from the oldest node). Warning when set to false: when some nodes are transferred, the first referential of the local map may change, resulting in momentary changes in robot/map position (which are annoying in teleoperation)." When set to true, the map is corrected instead the odometry position, assuming that the current robot position is the root of the graph. This is explained in Section II-B of this paper. 4) rtabmap node is always multi-session. Adding argument "delete_db_on_start" makes deleting the database on start. If the database is not deleted, a new map is automatically created in the loaded database and will be merged to an old map in the database when a loop closure is detected (with a location in a previous map). You can effectively use always the same database (with multiple maps inside). To initiate manually a new map without closing the rtabmap node, you can call service "/rtabmap/trigger_new_map". 5) In RVIZ, you can only visualize the edges of the current graph (without the vertices) using rtabmap/MapGraph display plugin. Regards, Mathieu |
Dear Mathieu,
Thank you for your detailed answer. Its really helpful. One more thing I would like to know, does rtabmap requires the RGBD sensor to be fixed on the robot ? Will it work if the xtion sensor is mounted with dynamixel motors and the sensor rotates in fixed plane (horizontal to the ground). Thanks Alex
------
Alex
|
Administrator
|
The sensor doesn't need to be fixed, but the TF between /base_link and /camera_link should be updated accordingly.
|
Free forum by Nabble | Edit this page |