introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
965 stars 557 forks source link

How to tune RTABMAP Parameters For a New Sensor Set and Environment #233

Closed aseyfi closed 5 years ago

aseyfi commented 6 years ago

Hello,

I am experimenting with a custom built RGBD+VIO sensor set. My end goal is to get a good occupancy map for my path planning algorithm and the best possible re-localization accuracy. I have seen some tutorials that explain different parameters and their purpose, but it is not clear to me the sequence of the steps for setting the parameters. What is the order in setting the parameters and how to judge in each step that I am using the best value? How should I know if my environment is friendly enough for RTAB? How should I evaluate my sensor calibration (intrinsic, extrinsic, timing), ...

Thank you very much in advance for your help.

Thanks, Ahmad

matlabbe commented 6 years ago

There is no standard path to follow, as quality is often dependent on the sensor accuracy/field-of-view/image size and the environment.

First, I would try to tune odometry settings, extracting more or less features, tuning the parameters of the visual feature type used. Here, you are using your own odometry approach, so you may be the better than me to tune it. If traversing a straight corridor and the corridor is bending always in the same direction, this is a good sign that the sensor may need better calibration. Having an accurate odometry will give better maps, and also add some robustness to system when localization against the map cannot be done for a couple of seconds.

For localization/loop closure, using very discriminative features like SURF or SIFT can help. To get better accuracy of the transformation computed, you can set RGBD/LoopClosureReextractFeatures to true and tune all parameters in Vis group of parameters ($ rtabmap --params | grep Vis/). Adjusting Vis/MinInliers can help to accept more localizations or less, increasing it would definitely increase accuracy at the cost of less localizations (when there are less matching visual features).

After that, it is more about the environment. In some environments, visual features can be lacking, so making localization difficult or even impossible, limiting the use of visual SLAM. RTAB-Map can then be used with lidars (2d or 3d) to get better accuracy in visually featureless environment while being highly geometric (great for lidar localization).

cheers, Mathieu

aseyfi commented 6 years ago

@matlabbe , Thank you very much, I will follow your suggestions. The odometry that I am using has about 1-2% drift and the depth image doesn't have 100% overlap with the gray image. Also, I have not evaluated time synchronization between the sensors. Is that something that I can evaluate based on the generated map, or I have to evaluate the timing separately?

Also, I have uploaded 3 bag files and two launch files in this link . I would appreciate if you take a look and let me know your thoughts and if you see obvious problems with my sensors or environment.

Thank You, Ahmad

matlabbe commented 6 years ago

You are using approx_sync set to false, the camera seems to give exact synchronization of depth and RGB. Browsing the data with DatabaseViewer and 3D view, the point cloud looks correctly registered to RGB image (color seems matching with geometry when the camera is moving). Right click on the image view and show depth to also see if depth matches to RGB.

Since your odometry doesn't drift a lot, I would set covariance to 0.0001 to rtabmap.launch include:

<arg name="odom_tf_angular_variance" value="0.0001"/>
<arg name="odom_tf_linear_variance" value="0.0001"/>

so that graph is better optimized on loop closures. Also, you may want to add to rtabmap_args --SURF/HessianThreshold 100 to extract more features. This helps getting more localizations on the relocalization0.bag where the camera is not at the same height than when mapping (point of view slightly different). For the relocalization1.bag, it localizes almost on every frame as the camera is at the same height than mapping phase.

In localization, I'll suggest that the camera always moves at the same height than at the mapping phase to have more localizations and more accurate loop closure transforms.

cheers, Mathieu

aseyfi commented 6 years ago

Hi @matlabbe ,

I followed you suggestions and here are the parameters that I am using:

  <include file="$(find rtabmap_ros)/launch/rtabmap.launch">
        <arg name="rtabmap_args" value="
--udebug
--logfile log1.txt
--delete_db_on_start
--RGBD/LoopClosureReextractFeatures true
--Mem/ImagePreDecimation 0 
--Mem/ImagePostDecimation 0 
--Rtabmap/DetectionRate 0 
--Rtabmap/ImageBufferSize 0 
--Kp/DetectorStrategy 0 
--Vis/BundleAdjustment 1
--Vis/CorGuessMatchToProjection false
--Vis/CorGuessWinSize 20
--Vis/CorNNDR 0.6 
--Vis/CorNNType 1
--Vis/CorType 0
--Vis/DepthAsMask true
--Vis/EpipolarGeometryVar 0.02
--Vis/EstimationType 1
--Vis/FeatureType 0
--Vis/ForwardEstOnly true
--Vis/GridCols 1
--Vis/GridRows 1
--Vis/InlierDistance 0.1
--Vis/Iterations 300
--Vis/MaxDepth 3.0
--Vis/MaxFeatures 1000
--Vis/MinDepth 0.5
--Vis/MinInliers 25
--Vis/PnPFlags 0
--Vis/PnPRefineIterations 0
--Vis/PnPReprojError 2
--Vis/RefineIterations 5
--Vis/SubPixEps 0.02
--Vis/SubPixIterations 0
--Vis/SubPixWinSize 3
--SURF/HessianThreshold 100
"/>
        <arg name="visual_odometry" value="false"/>
        <arg name="odom_frame_id" value="world"/>
        <arg name="frame_id" value="base_link"/>
        <arg name="rgb_topic" value="/image_rect/image_raw"/>
        <arg name="depth_topic" value="/depth_image"/>
        <arg name="camera_info_topic" value="/image_rect/camera_info"/>
        <arg name="compressed" value="true"/>
        <arg name="depth_image_transport" value="raw"/>
        <arg name="approx_sync" value="false"/>
        <arg name="queue_size" value="20"/>
        <arg name="wait_for_transform" value="1.0"/>
        <arg name="localization" value="false"/>
        <arg name="odom_tf_angular_variance" value="0.0001"/>
        <arg name="odom_tf_linear_variance" value="0.0001"/>
    </include>

At the end of the mapping process, I see some of the walls are not aligned properly. Here is a screenshot:

image

What could be causing this issue? Is is because I am not using correct rtabmap parameters for my data-set, or is it possible that I have some other sensor calibration/timing issues?

Thank You, Ahmad

matlabbe commented 6 years ago

The results I had with the previous launch (pressing "o" in the 3D view to get orthogonal view): screenshot_2018-04-10_11-41-16 Note how the walls have less errors than on your picture. Can you share the database corresponding to your picture? Maybe it is a version problem or dependencies missing on compilation.

By limiting the maximum depth to 3 meters of the generated clouds, I have: screenshot_2018-04-10_11-39-29 Which means that the sensor have some depth errors farther from the sensor, as the double walls were created from point clouds taken near and far from the surface.

cheers, Mathieu

aseyfi commented 6 years ago

Hi @matlabbe ,

I uploaded the file "mapping.db" to the same shared folder on Dropbox. I didn't have the database file corresponding to the screenshot, so I had to run rtabamap again using the parameters mentioned in my previous comment and the bag file "mapping.bag".

Regarding the depth sensor error, I can imagine two possibilities that can lead to multiple layers of walls. One can be depth sensor error and the other can be odometry error. How do we separate these two issues? Are the mapping issues due to odometry error look different than the ones because of depth sensor error?

Thanks, Ahmad

matlabbe commented 6 years ago

When I tested, as my rtabmap was not built with g2o, GTSAM was used for optimization, giving slightly better optimizations. I recompiled rtabmap with g2o, here g2o and GTSAM comparison (respectively): screenshot_2018-04-10_15-14-03 screenshot_2018-04-10_15-14-25

They are very similar on my system. The difference of g2o optimization between my system and yours is that on your system nodes are not added regularly (400 nodes instead of 600 nodes created on my system), which can affect optimization quality. Try setting Rtabmap/DetectionRate to 2 or 1 on the mapping phase, instead of 0. I tried it on my system and results are similar than trying to add as many nodes as possible.

If you limit the depth of the point cloud created and the map looks good, than you know that your depth sensor has more error at farther distance. If the maps don't look good, then there are some odometry errors. I see in this experiment that the camera is often looking right into a white wall, I think the odometry is drifting a little more when this happens. As odometry covariance is set the same when there are visual features and when there are very few, the graph optimization cannot know that it should put more errors in links where there were less features tracked.

cheers, Mathieu

aseyfi commented 6 years ago

We are using a fisheye camera for visual odometry and the images that we are using for rtabmap, are the same images that are undistorted and cropped. Here is an example of the images used for odometry: image

Following your comment about depth accuracy in longer distances, I carried out some experiments. I placed the camera 5.5m from a flat wall and collected the point cloud and projected the points on the XZ plane (looking at the points from top view). Here is the plot: image

As we can see, the average of the estimated depth is ~5.47m which is close to the measured value. Also, I may have some errors in measuring the actual distance of the camera from the wall. I carried out similar experiment using Lenovo Tango phone: image

It seems that my sensor is behaving pretty similar to Tango's sensor. My sensors shows some level of distortion in this distance and I have seen similar behavior from tango in different distance too. Can this distortion be the cause of the map miss-alignments?

To narrow done the problem, I disabled my odometry and I am using rtabmap's rgbd odometry (odometry parameters with their default values). I am trying to map a small space of 3x4m with lots of features. Before the loop closure happens, I see a lot of drift in odometry, here is the result from two different views: image

image

Is this drift a sign of rgb-d calibration issues? If yes, how can I find out if it is intrinsic calibration or the spatial calibration of the two sensors, or both that needs to be re-calibrated? Can it be one of the sources of the map miss-alignments that we have seen in my previous comments?

Thanks for your help, Ahmad

matlabbe commented 6 years ago

Hi,

For rgbd_odometry, the image usable (size of depth image) is quite small, so motion estimation will be very rough and will be a lot more sensible to featureless surfaces than VIO.

If the depth seems relatively accurate, the double wall would be caused by odometry. If you are looking for a very accurate setup, and debug calibration problems independently of the odometry accuracy, I suggest to create a ground truth using an external localization system (Vicon/HTC vive). Inject these poses to rtabmap instead of vo or vio with loop closure detection disabled (Kp/MaxFeatures=-1), then if there is still a double wall problem, it would be mostly a calibration problem. If the map looks very good, then the problem is coming from odometry. As I said in the previous post, the camera captures often images where large part of them are just textureless surfaces. This can cause some odometry drift higher at some places than others.

With RTAB-Map Tango, I generally suggest to avoid pointing the phone right in front of a texture less area, because VIO will drift lot more in this case and can cause some bad registrations in the map difficult to correct even with accurate loop closures.

cheers, Mathieu

aseyfi commented 6 years ago

Thanks Mathieu, I will follow your recommended path. You mentioned because of the low resolution, motion estimation would be rough. Does it mean even having a perfect map, I won't be able to get a good re-localization accuracy, because the resolution is low? Given the current resolutions and overlapped field of view and depth estimation accuracy, what would be the best re-localization and mapping accuracy that I can expect? Is there any formula for that?

Thanks, Ahmad

matlabbe commented 6 years ago

Well, the accuracy would be in the range of the sensor noise. Using your example above, if all features are at 5 meters, you can expect between 5 and 10 cm error. If depth error is +-2.5 cm at 2 meters for example, then localization error will be in that range. The size of the field of view would affect the number of localizations accepted (capacity to localize with slightly different point of views), but not their accuracy. Note that in contrast to odometry where we would want to still accept more erroneous transformations environments with low features to avoid lost odometry, if the depth image overlaps only textureless surface, there will be just no localization possible (thus localizations with large errors will be ignored) on RTAB-Map side. During that time, if odometry is relatively accurate, this would not be a problem. When the camera will be able to relocalize again with close and rich features, you will then get an accurate localization to correct the odometry drift accumulated since the previous localization.

cheers, Mathieu

aseyfi commented 6 years ago

Hi @matlabbe ,

Following your suggestion I prepared my motion capture setup to use it as source of odometry. I used this tool to calibrate the mocap rigid body markers respect to my robot base-frame. I disabled loop closure and here is an example of the generated map: image

I tried to use this map for relocalization using the exact bag file that was used for generating the map, I still see lots of jumps in estimated pose: image

How can I find the root-cause of the problem for each of this jumps given the fact that my map looks good (at least visually)? How can I see the image pairs that were used for motion estimation and the detected features and matched feature and the motion estimation error, for example reprojection error for each of the jumps during relocalization? I also uploaded a new bag file "optitrack_run2.bag" to the shared folder and two launch files that I used for mapping and re-localization.

Thanks, Ahmad

EDIT: The grid in the images are 10cmx10cm

matlabbe commented 6 years ago

Hi, The reprojection error is not available, but number of inliers is (View->Statistics->Loop tab). However, I checked and the number of inliers doesn't really correlate with highest errors. The biggest problem I see is that there is often loop closures where features are extracted from a small part of the image. Example: screenshot_2018-04-25_18-49-11 When showing up the 3D loop closure view on loop closure, we can see the registered clouds. Comparing with the RGB image on left with visual features extracted only at the corner of the room, the clouds are correctly overlapping there, but where there are no features, the clouds don't overlap well. Ideally, extracting features not only in depth image area but in all the RGB image could give more distributed features, and thus better motion estimation. Currently rtabmap can extract outside the depth image (Mem/DepthAsMask for loop closure detection and Vis/DepthAsMask for motion estimation), but won't use them for motion estimation, we would have to implement this.

cheers, Mathieu

Manoj-sanagapalli commented 5 years ago

Thanks Mathieu, I will follow your recommended path. You mentioned because of the low resolution, motion estimation would be rough. Does it mean even having a perfect map, I won't be able to get a good re-localization accuracy, because the resolution is low? Given the current resolutions and overlapped field of view and depth estimation accuracy, what would be the best re-localization and mapping accuracy that I can expect? Is there any formula for that?

Thanks, Ahmad

Hello People, I am trying autonomous navigation for a real robot using kinect camera. I am using rtabmap for mapping and localization. move_base is used for navigation to specified goal. map_server is used to convert my map in to "/mapData" format acceptable by move_base package.

move_base package is not getting proper localization position. I can see error in the estimated localization pose in rviz. Due to the error my move_base package is unable to navigate the bot. can anyone help me to solve my localization error.

Thank you.

matlabbe commented 5 years ago

Please open a new issue with more details, launch files used, maybe screenshots of the problem. You may also try this tutorial to see move_base + rtabmap integration.

cheers, Mathieu