Tips needed to improve on RTAB Mapping for legged Robots

Posted by derektan1995 on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Tips-needed-to-improve-on-RTAB-Mapping-for-legged-Robots-tp7417.html

Hi Matlabbe,

I have been spending the past few weeks reading up and experimenting on your RTAB implementation for ROS. Really appreciate the work that you have done in making such an amazing piece of technology open-sourced. I managed to come up with a rough map of an office environment, but I am still unsatisfied with the results.

I have mounted a intel realsense d435i, along with a 2d lidar sensor on my legged robot. The RGB image and depth information, along with laserscan and odometry values are recorded into a ROSbag. I did not use the IMU within the Realsense for odometry, rather, my odometry came from another IMU within the robot. The odometry value is corrected by the RTABMAP node by setting `Reg/Strategy` to 1. My starter code is based off of this ROS tutorial.

The frequency of topics the recording is limited due to recording large volume of information at once, but I thought it was sufficient given that the main RTAB node is running at 1Hz:
Laserscan: ~15Hz
Aligned depth cloud: ~12Hz
RBG Image: ~4Hz

Here is a video of the results:
https://youtu.be/FC21MHkqcUs

Here is a video of the 3d point cloud after post-processing the database:
https://youtu.be/83EHctnZ39E

Here is database of the results:
RTAB DB FILE

I have a few questions regarding how I can improve the map:
1) It seems like there are still lingering points along the walkway, as though the loop closure did not do a good job of stitching the depth cloud properly. I tried out almost all keypoint detectors and descriptors possible, but this is already the best possible configuration. Any idea on how I can improve this?


2) By the end of the simulation, there were only 5 loop closures detected, with 30 rejected. Is this normal? I attempted to use Vertigo using your tutorial on loop closure detection, but the results were worse off than this current configuration. It seems like the optimization resulted in an even more distorted map, even though there were significantly more loop closures and less rejected ones. Any insights on why this is so?

3) This question is more conceptual in nature. What is the purpose of the feeding in the depth cloud into the RTABmap node? Is it solely to construct a 3d map of the environment, stored as an octmap? Is this map used for Lidar ICP odometry correction, where the laserscan at each time step is compared against the Octmap to give a good estimation of the robot's odometry? Or is the odometry correction done by comparing the scan from previous timestep and the one at the current time step? Could I disable to construction of the 3D map if I wanted to?
(p.s. I am asking this question because I hope to eventually swap out the 2d lidar for a 3d Lidar as an input for more accurate scan matching. Ideally, I would like to use the 3d Lidar's input to construct the 3d map, especially since a 3d lidar have longer range than a typical RGBD camera. Would it be as simple as specifying the ''depth_topic" to be the 3d point cloud's topic? Or would another tool like Google's cartographer be more suitable for this? For outdoor applications, I would like to have 3D point cloud for ICP odometry correction and for map construction, and also at the same time using RGB input for global loop closure).

I welcome any other tips you might have! Here is my rtab mapping code. Thank you very much for your help!
rtab_mapping.launch:
<?xml version="1.0" encoding="UTF-8"?>

<launch>

  <arg name="database_path"     default="/home/$(env NAME)/.ros/rtabmap.db"/>
  <arg name="rgb_topic"         default="/camera/color/image_raw"/>
  <arg name="depth_topic"       default="/camera/aligned_depth_to_color/image_raw"/>
  <arg name="camera_info_topic" default="/camera/color/camera_info"/>
  <arg name="scan_topic"        default="/scan_filtered"/>  

  <group ns="rtabmap">

    <!-- 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="$(arg rgb_topic)"/>
      <remap from="depth/image"          to="$(arg depth_topic)"/>
      <remap from="rgb/camera_info"      to="$(arg camera_info_topic)"/>
      <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="true"/> 
    </node>

    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
          
      <!-- Sensor Input Parameters -->
      <param name="frame_id"             type="string" value="camera_link"/>
      <param name="subscribe_depth"      type="bool" value="false"/>
      <param name="subscribe_rgbd"       type="bool" value="true"/>
      <param name="subscribe_scan"       type="bool" value="true"/>
      <remap from="scan"                 to="$(arg scan_topic)"/>
      <remap from="rgbd_image"           to="rgbd_image"/>

      <!-- If odom_frame_id is empty, use odom message instead of tf -->
      <param name="odom_frame_id"        type="string" value=""/>            
      <remap from="odom"                 to="/odom"/>

      <!-- Output Params -->
      <param name="queue_size"           type="int" value="10"/>
      <remap from="grid_map"             to="/map"/>

      <!-- Rate (Hz) at which new nodes are added to map -->
      <param name="Rtabmap/DetectionRate"          type="string" value="1"/>

      <!-- RTAB-Map's parameters -->
      <param name="RGBD/NeighborLinkRefining"      type="string" value="true"/>  <!-- Correct odometry using the input lidar topic using ICP --> 
      <param name="RGBD/ProximityBySpace"          type="string" value="true"/>  <!-- Find local loop closures based on the robot position in the map. --> 
      <param name="RGBD/AngularUpdate"             type="string" value="0.01"/>  <!-- Map update Rate (Angular) -->
      <param name="RGBD/LinearUpdate"              type="string" value="0.01"/>  <!-- Map update Rate (Linear) -->
      <param name="RGBD/OptimizeFromGraphEnd"      type="string" value="false"/> <!-- FALSE: on loop closures the graph will be optimized from the first pose in the map -->
      <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="10"/>    <!-- Use 10 if Reg/Strategy is using ICP-->
      <param name="Grid/FromDepth"                 type="string" value="false"/> <!-- FALSE: the occupancy grid is created from the laser scans -->
      <param name="Reg/Force3DoF"                  type="string" value="true"/>  <!-- roll, pitch and z won't be estimated. -->
      <param name="Reg/Strategy"                   type="string" value="1"/>     <!-- 0=Visual, 1=ICP, 2=Visual+ICP -->
      
      <!-- ICP Loop Closure Detection (NOT IN USED) -->
      <param name="Optimizer/Strategy"             type="string" value="2"/>     <!-- g2o=1, GTSAM=2 -->
      <param name="Optimizer/Robust"               type="string" value="false"/> 
      <param name="RGBD/OptimizeMaxError"          type="string" value="6"/>

      <!-- 0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK 8=GFTT/ORB 9=KAZE -->
      <param name="Kp/DetectorStrategy"            type="string" value="2"/>     <!-- KEYPOINT DETECTOR -->
      <param name="Vis/FeatureType"                type="string" value="2"/>     <!-- KEYPOINT DESCRIPTOR -->
      <param name="Vis/MinInliers"                 type="string" value="15"/>    <!-- Minimum visual inliers to accept loop closure -->
      <param name="Kp/MaxDepth"                    type="string" value="0"/>     <!-- unlimited distance for the vocabulary  -->
      
      <!-- ICP parameters -->
      <param name="Icp/VoxelSize"                  type="string" value="0.05"/>  <!-- (DEFAULT: 0.0) -->
      <param name="Icp/MaxCorrespondenceDistance"  type="string" value="0.1"/>   <!-- (DEFAULT: 0.1) -->
      <param name="Icp/MaxTranslation"             type="string" value="0.5"/>   <!-- (DEFAULT: 0.2) -->
      <param name="Icp/MaxRotation"                type="string" value="0.78"/>  <!-- (DEFAULT: 0.78) -->
      <param name="Icp/Iterations"                 type="int"    value="50"/>    <!-- (DEFAULT: 30) -->

      <!-- Set to false to avoid saving data when robot is not moving -->
      <param name="Mem/NotLinkedNodesKept"         type="string" value="false"/>
  
    </node>
  </group>
</launch>
rtabmapviz.launch:
<?xml version="1.0" encoding="UTF-8"?>

<launch>
  <!-- Arguments for launch file with defaults provided -->
  <arg name="database_path"     default="/home/$(env NAME)/.ros/rtabmap.db"/>
  <arg name="rgb_topic"         default="/camera/color/image_raw"/>
  <arg name="depth_topic"       default="/camera/aligned_depth_to_color/image_raw"/>
  <arg name="camera_info_topic" default="/camera/color/camera_info"/>  
  <arg name="scan_topic"        default="/scan_filtered"/>  


  <!-- Mapping Node -->
  <group ns="rtabmap">

    <!-- visualization with rtabmapviz -->
    
    <node pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen">
    
        <param name="subscribe_depth"     type="bool"   value="false"/>
        <param name="subscribe_rgbd"      type="bool"   value="true"/>
        <param name="subscribe_rgb"       type="bool"   value="false"/>
        <param name="subscribe_scan"      type="bool"   value="true"/>

        <param name="frame_id"            type="string" value="base_link"/>

        <remap from="rgb/image"           to="$(arg rgb_topic)"/>
        <remap from="depth/image"         to="$(arg depth_topic)"/>
        <remap from="rgb/camera_info"     to="$(arg camera_info_topic)"/>
        <remap from="scan"                to="$(arg scan_topic)"/>
        <remap from="odom"                to="/odom"/>    
    </node>
  </group>
</launch>