Note: This tutorial assumes that you have completed the previous tutorials: Stereo Hand-Held Mapping, Setup RTAB-Map on Your Robot!.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Stereo Outdoor Mapping

Description: This tutorial shows how to do stereo mapping with RTAB-Map.

Tutorial Level: INTERMEDIATE

Next Tutorial: Stereo outdoor navigation

Introduction

In this demo, I will show how to setup RTAB-Map with only a Bumblebee2 stereo camera. The big advantage of using the stereo camera over the Kinect is for outdoor mapping. Unlike all my other demos with a robot so far, where it was constraint to the ground plane (3 DoF), here the robot (AZIMUT3) maps a 3D ground in 6DoF. Even if the map is 3D, a 2D occupancy grid map can be generated for navigation and obstacles can be detected.

Stereo azimut

3D Mapping

Configuration

setup_stereo

ROS bags

Launch

$ roslaunch rtabmap_demos demo_stereo_outdoor.launch
$ rosbag play --clock stereo_outdoorA.bag
[...]
$ rosbag play --clock stereo_outdoorB.bag

File demo_stereo_outdoor.launch (Updated 2015/10/31):

<launch>
   
   <!--
      Demo of outdoor stereo mapping. 
      From bag: 
      $ rosbag record 
            /stereo_camera/left/image_raw_throttle/compressed 
            /stereo_camera/right/image_raw_throttle/compressed 
            /stereo_camera/left/camera_info_throttle 
            /stereo_camera/right/camera_info_throttle 
            /tf
    
      $ roslaunch rtabmap_demos demo_stereo_outdoor.launch
      $ rosbag play -.-clock stereo_oudoorA.bag
   -->
   
   <!-- Choose visualization -->
   <arg name="rviz" default="true" />
   <arg name="rtabmap_viz" default="false" />
    
   <param name="use_sim_time" type="bool" value="True"/>
   
   <!-- Just to uncompress images for stereo_image_rect -->
   <node name="republish_left" type="republish" pkg="image_transport" args="compressed in:=/stereo_camera/left/image_raw_throttle raw out:=/stereo_camera/left/image_raw_throttle_relay" />
   <node name="republish_right" type="republish" pkg="image_transport" args="compressed in:=/stereo_camera/right/image_raw_throttle raw out:=/stereo_camera/right/image_raw_throttle_relay" />

   <!-- Run the ROS package stereo_image_proc for image rectification -->
   <group ns="/stereo_camera" >
      <node pkg="nodelet" type="nodelet" name="stereo_nodelet"  args="manager"/>
   
      <node pkg="stereo_image_proc" type="stereo_image_proc" name="stereo_image_proc">
         <remap from="left/image_raw"    to="left/image_raw_throttle_relay"/>
         <remap from="left/camera_info"  to="left/camera_info_throttle"/>
         <remap from="right/image_raw"   to="right/image_raw_throttle_relay"/>
         <remap from="right/camera_info" to="right/camera_info_throttle"/>
         <param name="disparity_range" value="128"/>
      </node>
   </group>
         
   <!-- Stereo Odometry -->   
   <node pkg="rtabmap_odom" type="stereo_odometry" name="stereo_odometry" output="screen">
      <remap from="left/image_rect"       to="/stereo_camera/left/image_rect"/>
      <remap from="right/image_rect"      to="/stereo_camera/right/image_rect"/>
      <remap from="left/camera_info"      to="/stereo_camera/left/camera_info_throttle"/>
      <remap from="right/camera_info"     to="/stereo_camera/right/camera_info_throttle"/>
      <remap from="odom"                  to="/stereo_odometry"/>

      <param name="frame_id" type="string" value="base_footprint"/>
      <param name="odom_frame_id" type="string" value="odom"/>

      <param name="Odom/Strategy" type="string" value="0"/> <!-- 0=BOW, 1=OpticalFlow -->
      <param name="Odom/EstimationType" type="string" value="1"/> <!-- 3D->2D (PnP) -->
      <param name="Odom/MinInliers" type="string" value="10"/>
      <param name="Odom/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/>
      <param name="Odom/MaxDepth" type="string" value="10"/>
      <param name="OdomBow/NNDR" type="string" value="0.8"/>
      <param name="Odom/MaxFeatures" type="string" value="1000"/>
      <param name="Odom/FillInfoData" type="string" value="$(arg rtabmap_viz)"/>
      <param name="GFTT/MinDistance" type="string" value="10"/>
      <param name="GFTT/QualityLevel" type="string" value="0.00001"/> 
   </node>
     
   <group ns="rtabmap">   
      <!-- Visual SLAM: args: "delete_db_on_start" and "udebug" -->
      <node name="rtabmap" pkg="rtabmap_slam" type="rtabmap" output="screen" args="--delete_db_on_start">
         <param name="frame_id" type="string" value="base_footprint"/>
         <param name="subscribe_stereo" type="bool" value="true"/>
         <param name="subscribe_depth" type="bool" value="false"/>

         <remap from="left/image_rect" to="/stereo_camera/left/image_rect_color"/>
         <remap from="right/image_rect" to="/stereo_camera/right/image_rect"/>
         <remap from="left/camera_info" to="/stereo_camera/left/camera_info_throttle"/>
         <remap from="right/camera_info" to="/stereo_camera/right/camera_info_throttle"/>

         <remap from="odom" to="/stereo_odometry"/>

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

         <!-- RTAB-Map's parameters -->
         <param name="Rtabmap/TimeThr" type="string" value="700"/>
         <param name="Rtabmap/DetectionRate" type="string" value="1"/>
         
         <param name="Kp/WordsPerImage" type="string" value="200"/>
         <param name="Kp/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/>
         <param name="Kp/DetectorStrategy" type="string" value="0"/>   <!-- use SURF -->
         <param name="Kp/NNStrategy" type="string" value="1"/>         <!-- kdTree -->

         <param name="SURF/HessianThreshold" type="string" value="1000"/>

         <param name="LccBow/MinInliers" type="string" value="10"/>
         <param name="LccBow/EstimationType" type="string" value="1"/> <!-- 3D->2D (PnP) -->

         <param name="LccReextract/Activated" type="string" value="true"/>
         <param name="LccReextract/MaxWords" type="string" value="500"/>
         <param name="LccReextract/MaxDepth" type="string" value="10"/> 
      </node>
      
      <!-- Visualisation RTAB-Map -->
      <node if="$(arg rtabmap_viz)" pkg="rtabmap_viz" type="rtabmap_viz" name="rtabmap_viz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen">
         <param name="subscribe_stereo" type="bool" value="true"/>
         <param name="subscribe_odom_info" type="bool" value="true"/>
         <param name="queue_size" type="int" value="10"/>
         <param name="frame_id" type="string" value="base_footprint"/>
         <remap from="left/image_rect" to="/stereo_camera/left/image_rect_color"/>
         <remap from="right/image_rect" to="/stereo_camera/right/image_rect"/>
         <remap from="left/camera_info" to="/stereo_camera/left/camera_info_throttle"/>
         <remap from="right/camera_info" to="/stereo_camera/right/camera_info_throttle"/>
         <remap from="odom_info" to="/odom_info"/>
         <remap from="odom" to="/stereo_odometry"/>
         <remap from="mapData" to="mapData"/>
      </node>
         
   </group>
  
   <!-- Visualisation RVIZ --> 
   <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="-d $(find rtabmap_demos)/launch/config/demo_stereo_outdoor.rviz"/>

</launch>

Results

persp_optimized

Odometry

With loop closures

Occupancy grid

grid_raw

grid_optimized

Top

top_raw

top_optimized

Side

side_raw

side_optimized

Community Stereo Odometry

You can run the bags with your odometry approach or with other community approaches. Here examples on how to use viso2_ros or fovis_ros with the launch file above.

viso2_ros

viso2_ros

   <node pkg="viso2_ros" type="stereo_odometer" name="stereo_odometer" output="screen">
      <remap from="stereo" to="/stereo_camera"/>
      <remap from="image" to="image_rect"/>
      <remap from="stereo_odometer/odometry" to="odometry" />

      <param name="base_link_frame_id" value="base_footprint"/>
      <param name="odom_frame_id" value="odom"/>
      <param name="ref_frame_change_method" value="1"/>
      <param name="queue_size" value="30"/>
   </node>
   
   <!-- rename camera info topics so viso2_ros can understand --> 
   <node name="camInfoL" type="relay" pkg="topic_tools" args="/stereo_camera/left/camera_info_throttle /stereo_camera/left/camera_info"/>
   <node name="camInfoR" type="relay" pkg="topic_tools" args="/stereo_camera/right/camera_info_throttle /stereo_camera/right/camera_info"/>     

fovis_ros

fovis_ros

<node pkg="fovis_ros" type="fovis_stereo_odometer" name="stereo_odometer" >
      <remap from="/stereo/left/image" to="/stereo_camera/left/image_rect" />
      <remap from="/stereo/right/image" to="/stereo_camera/right/image_rect" />
      <remap from="/stereo/left/camera_info" to="/stereo_camera/left/camera_info_throttle" />
      <remap from="/stereo/right/camera_info" to="/stereo_camera/right/camera_info_throttle" />
      <remap from="odometry" to="odometry" />
   </node>

Wiki: rtabmap_ros/Tutorials/StereoOutdoorMapping (last edited 2023-04-19 05:05:56 by MathieuLabbe)