ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

RTABMAP 3D map errors

asked 2018-07-21 11:48:05 -0600

Dox gravatar image

updated 2018-07-21 12:03:36 -0600

Hi, I'm trying to build a 3D map remotely with RTABMap over WiFi. I'm running a navigation stack, Rosaria, freenect and depthimage_to_laserscan nodes on Raspberry Pi 3 which is interfaced with Kinect Xbox 360 camera and Pioneer robot. RTABMap and RViz nodes are running on my laptop. ROS Kinetic is installed on both computers with Ubuntu 14.04 LTS 32-bit on laptop and Ubuntu Mate on RPi3.

Here are some screenshots of 3D maps I've build so far. Let's say these are the least bad.

1.) I've tried experimenting with different velocity rates, slowing vel_x and vel_theta down to 0.1 m/s. Maybe it did reduce misalignment a bit, but 3D map still has considerable amount of error.

2.) I am not sure if I should try calibrating my Kinect, since Freenect loads default calibration settings every time it starts.

3.) I have one static TF transform between robot base_link and camera_link which I've set up following this tutorial. Kinect is positioned 17,5 cm at the back on x-axis and 56,7 cm from the center of robot's base to the center of kinect.

<node pkg="tf" type="static_transform_publisher" name="base_to_camera_tf" args="-0.175 0.0 0.567 0 0 0 /base_link /camera_link 100" <="" p="">

I am not sure if I should also have base_footprint between /odom and /base_link. I did notice that there is as a map offset in RviZ. This is how my TF frames look like.

4.) Could it be that robot using skid steering drive leads to odometry drift? Even if I am trying to map a small scale space, a room that is 5,5 m x 4,5 m.

5.) Would some parameter tunning improve the performance? I also tried throttling frame rate but I would not say that it had any considerable effect on reducing the errors. I am currently using these:

    <param name="RGBD/ProximityBySpace"     type="string" value="false"/>
      <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="Optimizer/Slam2D"          type="string" value="true"/>
      <param name="Reg/Strategy"              type="string" value="1"/> <!-- 1=ICP -->
      <param name="Reg/Force3DoF"             type="string" value="true"/>
      <param name="Vis/MaxDepth"              type="string" value="4.0"/>
      <param name="Vis/MinInliers"            type="string" value="5"/>
      <param name="Vis/InlierDistance"        type="string" value="0.05"/>
      <param name="Rtabmap/TimeThr"           type="string" value="700"/>
      <param name="Mem/RehearsalSimilarity"   type="string" value="0.45"/>
      <param name="Icp/CorrespondenceRatio"   type="string" value="0.5"/>
      <!-- Added -->
      <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"/>

I'm stuck ATM, since I do not know what to try next to improve the quality of 3D map. Any suggestions would be much appreciated. Thanks!

edit retag flag offensive close merge delete

Comments

Can you share a database? From the screenshots, errors seem coming from the odometry drift and/or not precise tf between base_link and camera_link.

matlabbe gravatar image matlabbe  ( 2018-07-24 15:25:25 -0600 )edit

I couldn't find a database that corresponds to those specific screenshots since I have many. This one is even messier. If you need more db or anything else, please let me know.

Dox gravatar image Dox  ( 2018-07-25 07:43:11 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2018-07-25 18:34:41 -0600

matlabbe gravatar image

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:

image description

Synchronization between RGB-D data and scan is sometimes poor, does the scan is coming from the same depth image fed to rtabmap?

image description

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? image description

Here is the map without loop closure optimizations, only odometry from the robot: image description

With loop closures: image description

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: image description

with loop closures: image description

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:

image description

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

edit flag offensive delete link more

Comments

Thank you for your thorough analysis and clarification Mathieu.

I don't know how to improve the robot's odometry atm, so I'll try with visual odometry as you suggested. Basically, I need to replace ROSAria's odom for rtabmap rgbd_odometry node, right? I'll test it and get back with results asap.

Dox gravatar image Dox  ( 2018-07-26 16:13:30 -0600 )edit

Hi Mathieum when trying to use rtabmap_ros/rgbd_sync nodelet as u suggested I get the following error: Failed to load nodelet [/camera/rgbd_sync] of type [rtabmap_ros/rgbd_sync] even after refreshing the cache: Failed to load library /opt/ros/kinetic/lib//librtabmap_ros.so. Make sure that you are...

Dox gravatar image Dox  ( 2018-08-14 07:13:38 -0600 )edit

...calling the PLUGINLIB_EXPORT_CLASS macro in the library code, and that names are consistent between this macro and your XML. Error string: Could not load library (Poco exception = librtabmap_core.so.0.17: cannot open shared object file: No such file or directory)

Dox gravatar image Dox  ( 2018-08-14 07:14:16 -0600 )edit

Hi, rgbd_sync should be in the released binaries for kinetic. Is ros-kinetic-rtabmap-ros updated to latest version?

matlabbe gravatar image matlabbe  ( 2018-08-14 08:28:09 -0600 )edit

I have v 0.17 installed. I also get this:

Client [/rtabmap/rtabmap] wants topic /camera/rgbd_image/compressed to have datatype/md5sum [rtabmap_ros/RGBDImage/a7fa8f34f44b976b3b2dec13c02f9f0e], but our version has [rtabmap_ros/RGBDImage/e2918ceee8cb5b4c4b0007166508b871]. Dropping connection.
Dox gravatar image Dox  ( 2018-08-15 06:13:27 -0600 )edit
1

Make sure you have the same version on both computers. The topic didn't change since 0.17.0 release.

matlabbe gravatar image matlabbe  ( 2018-08-15 08:36:01 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2018-07-21 11:48:05 -0600

Seen: 1,430 times

Last updated: Jul 25 '18