ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Hi,
Looking at the database, odometry from your robot is drifting quite much at some places, here is an example between two captures 1 second apart:
Synchronization between RGB-D data and scan is sometimes poor, does the scan is coming from the same depth image fed to rtabmap?
When using scan from RGB-D camera, don't use these parameters:
<param name="Reg/Strategy" type="string" value="1"/> <!-- 1=ICP -->
<param name="Odom/Strategy" type="string" value="1"/> <!-- Frame-to-Frame odometry -->
<param name="Odom/GuessMotion" type="string" value="true" />
<param name="Vis/EstimationType" type="string" value="1"/> <!-- 2D->3D PnP -->
<param name="Vis/CorType" type="string" value="1"/>
Synchronization between RGB and Depth is also poor sometimes, what is the frame rate of rgb and depth images?
Here is the map without loop closure optimizations, only odometry from the robot:
With loop closures:
I am quite surprised that the map is quite good for as much odometry noise.
I did reprocessed the database, but computing visual odometry instead, here are the results, without loop closures:
with loop closures:
Note that visual odometry should give better results than that when processing at higher frame rate than 1 Hz here. The optimized results are good enough to generate a mesh though:
In conclusion, you may try to increase accuracy of your robot odometry, or switch to visual odometry. However, as you are using a RPI3 on the robot, you may not be able to stream as fast the images to remote computer so that odometry can be done higher than 10 Hz. For the synchronization problem, I think it is coming from the network as rtabmap is running offboard. You may try to use rtabmap_ros/rgbd_sync nodelet to synchronize RGB, depth and camera_info message on RPI before sending the synchronized rtabmap_ros/RGBDImage message to rtabmap offboard. On the robot:
<group ns="camera">
<node pkg="nodelet" type="nodelet" name="rgbd_sync" args="load rtabmap_ros/rgbd_sync camera_nodelet_manager">
<remap from="rgb/image" to="/camera/rgb/image_rect_color"/>
<remap from="depth/image" to="/camera/depth_registered/image_raw"/>
<remap from="rgb/camera_info" to="/camera/rgb/camera_info"/>
</node>
</group>
Then on laptop, start rtabmap
with subscribe_rgbd:=true
:
<param name="subscribe_depth" type="bool" value="false"/>
<param name="subscribe_rgbd" type="bool" value="true"/>
<remap from="rgbd_image" to="/camera/rgbd_image/compressed"/>
cheers,
Mathieu