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

Rtabmap deletes part of map

asked 2017-04-15 16:11:43 -0500

Timo1804 gravatar image

updated 2017-04-19 09:23:34 -0500

matlabbe gravatar image

I am running Ubuntu Mate 16.04 on Raspberry Pi 3 and have tried to build a map with rtabmap. I am using Kinect, fake lasermsg from Kinect, odometry from wheel encoders and imu. Rtabmap is running on the Raspberry Pi and the visualisation with Rviz on a remote computer. When the robot drives around, he builds the map quiet well but deletes these parts of the map, where he is not right now.

Launchfile:

<launch>

<!-- Connection + Driving: -->
<include file="$(find differential_drive)/launch/start_minimal.launch"/>

<!-- Urdf-Model + Transform: -->
<include file="$(find drink_description)/launch/load_urdf.launch"/>

<!-- Kinect + depthimage_to_laserscan: -->
<include file="$(find differential_drive)/launch/freenect_rtab.launch"/>

<!-- Robot_Localization (Combines Odom + Imu): -->
<include file="$(find drink_mapping)/launch/robot_localization.launch"/>

<!-- SLAM: -->
<group ns="rtabmap">
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
          <param name="frame_id" type="string" value="base_footprint"/>

          <param name="subscribe_depth" type="bool" value="true"/>
          <param name="subscribe_scan" type="bool" value="true"/>

          <remap from="odom" to="/odometry/filtered"/>
          <remap from="scan" to="/kinect_scan"/>

          <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"/>

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

      <param name="wait_fot_transform_duration" value="0.5"/>
      <param name="approx_sync" value="true"/>


          <!-- RTAB-Map's parameters -->
          <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="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="3"/>
          <param name="Vis/InlierDistance"        type="string" value="0.1"/>
          <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"/>
          <param name="Grid/FromDepth"            type="string" value="false"/>
    </node>
  </group>
</launch>

Warning:

[ WARN] (2017-04-15 22:28:21.616) Rtabmap.cpp:1786::process() Rejected loop closure 803 -> 819: Cannot compute transform (cor=90 corrRatio=0.140625/0.500000)
[ WARN] (2017-04-15 22:28:21.626) Memory.cpp:1580::forget() Less signatures transferred (0) than added (3)! The working memory cannot decrease in size.
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2017-04-19 09:34:16 -0500

matlabbe gravatar image

Hi,

<param name="Rtabmap/TimeThr"           type="string" value="700"/>

is set (not 0), so memory management of RTAB-Map is enabled. This is explained in Online Global Loop Closure Detection for Large-Scale Multi-Session Graph-Based SLAM.

When updating the map requires for than 700 ms, some nodes in the map will be transferred to Long-Term Memory, making some parts of the map disappearing. However, if the robot navigates again towards these areas, they should re-appear (e.g., like if the robot remembers previous areas). If Rtabmap/TimeThr is 0 (disabled), you will keep always the full global map, but at cost of not having map updates done online (more and more time is required to update the map). You should see info messages on terminal telling the current processing time used for map updates.

cheers, Mathieu

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2017-04-15 16:11:43 -0500

Seen: 574 times

Last updated: Apr 19 '17