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

Rtabmap problem with octomap

asked 2019-04-09 09:36:38 -0500

VagZikopis gravatar image

updated 2019-04-09 09:43:42 -0500

Hello, I have a problem when running rtabmap SLAM algorithm in my real turtlebot. Specifically, when I visualize octomap in rviz, the map seems to have a limit at the top of the room. I suppose that it shows the room’s ceiling but it could also be sensor’s noise. I use: Turtlebot 2 with Ubuntu 16.04 and ROS kinetic, my camera is Asus Xtion Pro and my computer has Ubuntu 16.04 and ROS kinetic.

Firstly, how could I understand if this limit in octomap is room’s ceiling or sensor’s noise and furthermore how can I throw these nodes in octomap in order to see room’s details?

The launcher I use to run rtabmap is:

<launch>

     <arg name="database_path"     default="rtabmap.db"/>
     <arg name="rgbd_odometry"     default="false"/>
     <arg name="rtabmapviz"        default="false"/>
     <arg name="localization"      default="false"/>
     <arg name="simulation"        default="false"/>
     <arg name="sw_registered"     default="false"/>
     <arg     if="$(arg localization)" name="args"  default=""/>
     <arg unless="$(arg localization)" name="args"  default="--delete_db_on_start"/>

    <arg     if="$(arg simulation)" name="rgb_topic"   default="/camera/rgb/image_raw"/>
    <arg unless="$(arg simulation)" name="rgb_topic"   default="/camera/rgb/image_rect_color"/>
    <arg     if="$(arg simulation)" name="depth_topic" default="/camera/depth/image_raw"/>
    <arg unless="$(arg simulation)" name="depth_topic" default="/camera/depth_registered/image_raw"/>
    <arg name="camera_info_topic" default="/camera/rgb/camera_info"/>

    <arg name="wait_for_transform"  default="0.2"/>

<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="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="false"/>
      <param name="map_negative_poses_ignored" type="bool" value="true"/>

      <!-- inputs -->
      <remap from="scan"            to="/scan"/>
      <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 unless="$(arg rgbd_odometry)" from="odom" to="/odom"/>

      <!-- 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="2"/>      <!-- Loop closure transformation: 0=Visual, 1=ICP, 2=Visual+ICP -->
      <param name="Icp/CorrespondenceRatio"      type="string" value="0.3"/>
      <param name="Vis/MinInliers"               type="string" value="15"/>      <!-- 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 -->
      <param name="RGBD/LinearUpdate"            type="string" value="0.1"/>    <!-- Update map only if the robot is moving -->
      <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="0"/>
      <param name="Rtabmap/TimeThr"              type="string" value="700"/>
      <param name="Mem/RehearsalSimilarity"      type="string" value="0.30"/>
      <param name ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2019-04-09 23:33:52 -0500

matlabbe gravatar image

Try adding this under rtabmap node:

<param name="Grid/MaxObstacleHeight" type="string" value="1.5"/>

This should only keep obstacles under 1.5 meters.

cheers,
Mathieu

edit flag offensive delete link more

Comments

With your tip, the map stopped having issues with the top of the room but after some navigation time, the algorithm still produces errors on the obstacles that the sensors detect. Any idea on this? Here are some pictures. image_1image_2

VagZikopis gravatar image VagZikopis  ( 2019-04-11 16:03:13 -0500 )edit

It is difficult to see which obstacles are wrong and which are correct. Note that you can use rtabmap-databaseViewer, open 3D View, check grid checkbox and scroll images to see which one is causing the wrong obstacles.

matlabbe gravatar image matlabbe  ( 2019-04-12 21:22:39 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-04-09 09:36:38 -0500

Seen: 1,004 times

Last updated: Apr 09 '19