Re: Issue Getting Map from Rtabmap
Posted by
matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Issue-Getting-Map-from-Rtabmap-tp6068p6072.html
Hi,
For rgbd_odometry, I would choose between the nodelet version or not, to avoid confusion between both (they even have different parameters). As you are doing fusion of odometry, make sure to disable
publish_tf from rgbd_odometry node to avoid conflict with tf published by robot_localization for example.
<!-- under rgbd_odometry node -->
<param name="publish_tf" value="false"/>
I don't recommend synchronizing all those topics together:
<remap from="odom" to="/odom1"/>
<remap from="scan_cloud" to="/velodyne_points"/>
<remap from="depth/image" to="/camera/aligned_depth_to_color/image_raw"/>
<remap from="rgb/camera_info" to="/camera/color/camera_info"/>
<remap from="rgb/image" to="/camera/color/image_raw"/>
Like in the
examples on this page, use
rgbd_sync nodelet if you are synchronizing images with a lidar or external odometry (not synced with images). In your case, it would look like this:
<!-- Use RGBD synchronization -->
<!-- Here is a general example using a standalone nodelet,
but it is recommended to attach this nodelet to nodelet
manager of the camera to avoid topic serialization -->
<node pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/rgbd_sync" output="screen">
<remap from="rgb/image" to="/camera/color/image_raw"/>
<remap from="depth/image" to="/camera/aligned_depth_to_color/image_raw"/>
<remap from="rgb/camera_info" to="/camera/color/camera_info"/>
<remap from="rgbd_image" to="rgbd_image"/> <!-- output -->
<!-- Should be true for not synchronized camera topics
(e.g., false for kinectv2, zed, realsense, true for xtion, kinect360)-->
<param name="approx_sync" value="false"/>
</node>
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
<param name="frame_id" type="string" value="base_link"/>
<param name="subscribe_depth" type="bool" value="false"/>
<param name="subscribe_rgbd" type="bool" value="true"/>
<param name="subscribe_scan_cloud" type="bool" value="true"/>
<remap from="odom" to="/odom1"/>
<remap from="scan_cloud" to="/velodyne_points"/>
<remap from="rgbd_image" to="rgbd_image"/>
<param name="queue_size" type="int" value="10"/>
<param name="approx_sync" type="bool" value="true"/>
<!-- RTAB-Map's parameters -->
<param name="RGBD/NeighborLinkRefining" type="string" value="true"/>
<param name="RGBD/ProximityBySpace" type="string" value="true"/>
<param name="RGBD/AngularUpdate" type="string" value="0.01"/>
<param name="RGBD/LinearUpdate" type="string" value="0.01"/>
<param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>
<param name="Grid/FromDepth" type="string" value="false"/> <!-- occupancy grid from lidar -->
<param name="Reg/Force3DoF" type="string" value="true"/> <!-- 2D mapping? -->
<param name="Reg/Strategy" type="string" value="1"/> <!-- 1=ICP -->
<!-- ICP parameters -->
<param name="Icp/VoxelSize" type="string" value="0.2"/>
<param name="Icp/MaxCorrespondenceDistance" type="string" value="0.2"/>
</node>
Note that approx_sync should be true for rtabmap node, as velodyne and camera topics would not be exactly synchronized. This is probably the reason why the map was empty (though I am surprised you didn't have warnings about rtabmap not receiving topics...).
cheers,
Mathieu