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

Using RTABMAP with Gmapping?

asked 2017-05-04 11:28:19 -0500

schrottulk gravatar image

updated 2017-05-04 11:29:21 -0500

Hi there!

I am building a map with a Kinect 360, a RPLidar-laserscanner and a turtlebot using RTABMAP on Ubuntu 14.04 and ROS Indigo. Hi,

While using RTABMAP I get poor results for the registered 3D Point Cloud and the 2D grid_map (which I am using for navigation). There a many registration errors in both map. So I decided to use gmapping for building the 2D map and run rtabmap in parallel. I set "publish_tf" to false and got really good results for the 2D Map, but still poor results in the 3D point cloud. Is it possible in RTABMAP to prior the laserscanner data for RTABMAPs scan-matching and pose estimation? Or to use gmappings pose estimation for RTABMAPs point cloud registration?

Or does anyone now another package to register the point clouds from kinect?

I am using this launch file from now:

<launch>

  <arg name="database_path"     default="rtabmap.db"/>
  <arg name="localization"      default="false"/>
  <arg name="rgbd_odometry"     default="false"/>
  <arg name="args"              default="--delete_db_on_start"/>
  <arg name="rtabmapviz"        default="false"/>

  <arg name="wait_for_transform"  default="0.2"/> 
  <!-- 
      robot_state_publisher's publishing frequency in "turtlebot_bringup/launch/includes/robot.launch.xml" 
      can be increase from 5 to 10 Hz to avoid some TF warnings.
  -->

  <!-- Navigation stuff (move_base) -->
  <include file="$(find turtlebot_bringup)/launch/3dsensor.launch">
    <arg name="scan_processing"  value="false" />                      <!-- Disable conversion from Kinect to /scan -->
  </include>

  <!-- gmapping -->
  <include file="$(find turtlebot_igm)/launch/gmapping.launch"/>

  <include file="$(find turtlebot_navigation)/launch/includes/move_base.launch.xml"/>

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

    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="$(arg args)">
      <param name="database_path"       type="string" value="$(arg database_path)"/>
      <param name="frame_id"            type="string" value="base_footprint"/>
      <param name="odom_frame_id"       type="string" value="odom"/>
      <param name="wait_for_transform_duration"  type="double"   value="$(arg wait_for_transform)"/>
      <param name="subscribe_depth"     type="bool"   value="true"/>
      <param name="subscribe_scan"      type="bool"   value="true"/>


    <!--<param name="Grid/FromDepth" type="string" value="true" />-->
    <param name="publish_tf"         type="bool"   value="false"/>
    <param name="RGBD/PoseScanMatching" type="bool" value="true"/>

      <!-- inputs -->
      <remap from="scan"            to="/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"/>

      <!-- output -->
      <!--<remap from="grid_map" to="/map"/>-->

      <!-- RTAB-Map's parameters: do "rosrun rtabmap rtabmap (double-dash)params" to see the list of available parameters. -->
      <param name="RGBD/ProximityBySpace"        type="string" value="true"/>   <!-- Local loop closure detection (using estimated position) with locations in WM -->
      <param name="RGBD/OptimizeFromGraphEnd"    type="string" value="false"/>  <!-- Set to false to generate map correction between /map and /odom -->
      <param name="Kp/MaxDepth"                  type="string" value="4.0"/>
      <param name="Reg/Strategy"                 type="string" value="1"/>      <!-- Loop closure transformation refining with ICP: 0=Visual, 1=ICP, 2=Visual+ICP -->
      <param name="Icp/CoprrespondenceRatio"     type="string" value="0.3"/>
      <param name="Vis/MinInliers"               type="string" value="5"/>      <!-- 3D visual words minimum inliers to accept loop closure -->
      <param name="Vis/InlierDistance"           type="string" value="0.1"/>    <!-- 3D visual words correspondence distance -->
      <param name="RGBD/AngularUpdate"           type="string" value="0.1"/>    <!-- Update map only if the robot is moving ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2017-05-05 11:09:50 -0500

matlabbe gravatar image

rtabmap and gmapping are not compatible. Their map structure is different: rtabmap is a graph and gmapping is multiple 2d occupancy grid maps (one for each particle of its particle filter). If gmapping closes a loop, there is no way to tell rtabmap how rtabmap's nodes should be corrected to match the poses in gmapping (of its current best map).

With your settings, rtabmap should give relatively good maps. Maybe Icp parameters could be tuned to get better results:

$ rosrun rtabmap_ros rtabmap --params | grep Icp
Param: Icp/CorrespondenceRatio = "0.2" [Ratio of matching correspondences to accept the transform.]
Param: Icp/DownsamplingStep = "1" [Downsampling step size (1=no sampling). This is done before uniform sampling.]
Param: Icp/Epsilon = "0"  [Set the transformation epsilon (maximum allowable difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution.]
Param: Icp/Iterations = "30"  [Max iterations.]
Param: Icp/MaxCorrespondenceDistance = "0.05"   [Max distance for point correspondences.]
Param: Icp/MaxRotation = "0.78"   [Maximum ICP rotation correction accepted (rad).]
Param: Icp/MaxTranslation = "0.2"    [Maximum ICP translation correction accepted (m).]
Param: Icp/PointToPlane = "false"     [Use point to plane ICP.]
Param: Icp/PointToPlaneNormalNeighbors = "20"   [Number of neighbors to compute normals for point to plane.]
Param: Icp/VoxelSize = "0.0"     [Uniform sampling voxel size (0=disabled).]
Param: Reg/Strategy = "0"        [0=Vis, 1=Icp, 2=VisIcp]

For example, Icp/CorrespondenceRatio could be lowered or Icp/MaxCorrespondenceDistance increased to accept more Icp refined transforms between added poses to map.

cheers,

Mathieu

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2017-05-04 11:28:19 -0500

Seen: 1,914 times

Last updated: May 05 '17