Robust SLAM w/Vertigo Questions

classic Classic list List threaded Threaded
3 messages Options
Reply | Threaded
Open this post in threaded view
|

Robust SLAM w/Vertigo Questions

aarif
Hi Matthieu,

I was able to successfully implement RTAB-Map on ROS using Vertigo (w/g2o). I've tested it with a loop and was really pleased with the results. I chose the following values in my launch file to make RTAB-Map work with Vertigo:

<rosparam name="RGBD/OptimizeMaxError" type="string" value="0"/> <!- disabled as Optimizer/Robust is enabled-->
<rosparam name="Optimizer/Strategy"    type="string" value="1"/> <!- 1=g2o 2=GTSAM -->
<rosparam name="Optimizer/Robust"      type="string" value="true"/> <!- disabled -->
<rosparam name="Rtabmap/LoopThr" type="string" value="0.65"/> <!-- Setting it over 0.5 may reduce the chance of false positive hypotheses -->
<rosparam name="Mem/STMSize"     type="string" value="25"/> <!-- For long corridors, you may want to set it over 20 -->
I have two questions regarding Vertigo in RTAB-Map:

1. Is there a way to observe the map being created using Veritgo? Usually when I run RTAB-Map without Veritgo, I can watch the map being created and see how the map does loop closure. I'm hoping I can do the same when I'm using Vertigo.

2. I chose the values for Rtabmap/LoopThr and Mem/STMSize arbitrarily based off of your recommendations. How can I choose the best-possible values? I'm currently combing through Latif, Cadena, and Neira (2013) paper, but I'm not finding a good answer to this question that I can understand.

Thank you for your time,
Abdul
Reply | Threaded
Open this post in threaded view
|

Re: Robust SLAM w/Vertigo Questions

matlabbe
Administrator
Hi,

1) Normally you should see the same thing as without Vertigo, like in the video of this tutorial: https://github.com/introlab/rtabmap/wiki/Robust-Graph-Optimization. Just tried with 0.11.11 and g2o and it works like in the video (not sure why with GTSAM that didn't work for me though). To see the black lines in rtabmapviz, don't forget that note of the tutorial:
Note: to actually see the black lines as in the video, you should set "Reject loop closures if optimization error is greater than this value (0=disabled)." to 0, then when back to the main window right-click on the Graph View -> "Set link color..." -> "Set outlier threshold..." and set value to 1 m.
2) Rtabmap/LoopThr default value (0.11) is based on results of this paper (with corresponding datasets, min T_loop in table II and II). In practice, I almost never change it. I let the geometric verification rejecting false positives (Vis/MinInliers, default 20). For Mem/STMSize (default 10), it should be enough large to avoid loop closure on just seen locations, like described in the referred paper above:
Similar to [17], RTAB-Map does not use locations in STM
to avoid loop closures on locations that have just been visited
(because most of the time, the last location frequently looks
similar to the most recent ones).  The STM size TSTM is
set based on the robot velocity and the rate at which the
locations are acquired.
As pointed out in the comment in your rosparam: "For long corridors, you may want to set it over 20", I've found that for very long repetitive corridors, it is not a good solution. The best solution I've found is to reduce RGBD/OptimizeMaxError to 0.05 meter (without Vertigo, and assuming that odometry covariance is always under that value).

cheers,
Mathieu

Reply | Threaded
Open this post in threaded view
|

Re: Robust SLAM w/Vertigo Questions

aarif
Hi Matthieu,

Thank you for your response. I'm using ROS Indigo, so I'm using version 0.11.8. The part of the launch file that involves rtabmap_ros and rtabmapviz are as follows:

  <group ns="rtabmap">

    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" args="--delete_db_on_start" required="true">

      <param name="frame_id"             type="string" value="base_link"/>
      <param name="subscribe_depth"      type="bool" value="true"/>
      <param name="subscribe_laserScan"  type="bool" value="true"/>

      <remap from="odom"            to="$(arg odom_topic)"/>
      <remap from="scan"            to="$(arg scan_topic)"/>
      <remap from="rgb/image"       to="$(arg rgb_topic)"/>
      <remap from="depth/image"     to="$(arg depth_registered_topic)"/>
      <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>

      <param name="scan_voxel_size"              type="str"      value="0.01" />
      <param name="queue_size"                   type="int"      value="10"/>

      <!-- RTAB-Map's parameters -->
      <param name="RGBD/AngularUpdate" type="string" value="0.01"/>
      <param name="RGBD/LinearUpdate" type="string" value="0.01"/>
      <param name="Rtabmap/TimeThr" type="string" value="700"/>
      <param name="Mem/RehearsalSimilarity" type="string" value="0.45"/>
      <param name="RGBD/OptimizeFromGraphEnd" type="string" value="true"/>

      <param name="RGBD/OptimizeMaxError"        type="string"   value="0"/> <!-- disabled as Optimizer/Robust is enabled-->
      <param name="Optimizer/Strategy"           type="string"   value="1"/> <!-- 1=g2o 2=GTSAM -->
      <param name="Optimizer/Robust"             type="string"   value="true"/> <!-- disabled -->
      <param name="Rtabmap/LoopThr"              type="string"   value="0.65"/> <!-- Setting it over 0.5 may reduce the chance of false positive hypotheses -->
      <param name="Mem/STMSize"                  type="string"   value="25"/> <!-- For long corridors, you may want to set it over 20 -->

    </node>

  </group>

  <node pkg="topic_tools" type="relay" name="map_relay" args="/rtabmap/grid_map /map" />

  <node pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="$(arg rtabmapviz_cfg)" launch-prefix="" respawn="true">

    <param name="subscribe_depth"       type="bool"   value="true"/>
    <param name="subscribe_scan"        type="bool"   value="$(arg subscribe_scan)"/>
    <param name="subscribe_scan_cloud"  type="bool"   value="$(arg subscribe_scan_cloud)"/>
    <param name="subscribe_odom_info"   type="bool"   value="$(arg visual_odometry)"/>
    <param name="frame_id"              type="string" value="base_link"/>
    <param name="wait_for_transform_duration"  type="double"   value="0.2"/>

    <remap from="rgb/image"       to="$(arg rgb_topic)"/>
    <remap from="depth/image"     to="$(arg depth_registered_topic)"/>
    <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>
    <remap from="scan"            to="$(arg scan_topic)"/>
    <remap from="scan_cloud"      to="$(arg scan_cloud_topic)"/>
    <remap unless="$(arg visual_odometry)" from="odom"  to="$(arg odom_topic)"/>

  </node>

1) Ok, I'll look into the parameters that I've changed in the following days and let you know. To be honest, I'm more interested in seeing the map close its loops rather than observing the rejected loop closures. Perhaps I mistyped one of the parameters. I just wanted to make sure that this wasn't a by-product of using Vertigo.

2) Thank you for your comments on changing these parameters, I'll leave Rtabmap/LoopThr and Mem/STMSize alone and rely on geometric verification to reject the false positives and Mem/STMSize's default value is large enough to avoid incorrect loop closures on recent locations.

Relying on odometry for our robot for loop closures is not possible for us since our robot has wheel encoders that build up error over time and it's expected to run for a long period of time. However, our university's corridors are not, in my opinion, too long per se, but we'll only figure that out after many tests.

Thank you for your advice Matthieu, I'll test it out in the next few days and let you know if any issues arise!

Thanks,
Abdul