Note: This tutorial assumes that you have completed the previous tutorials: RGB-D Hand-Held Mapping With a Kinect, 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.

Mapping and Navigation with Turtlebot

Description: This tutorial shows how to use RTAB-Map with Turtlebot for mapping and navigation.

Tutorial Level: INTERMEDIATE

Next Tutorial: Stereo Outdoor Mapping

Introduction

(Originally from this post from RTAB-Map's forum)

For Turtlebot3 on Melodic/Noetic, see below.

This page will show how to use rtabmap on a Turtlebot. I don't own a Turtlebot, so I've made a launch file from what I can test without the actual robot. The launch file demo_turtlebot_mapping.launch is a one to one replacement of the gmapping_demo.launch of the official SLAM Map Building with TurtleBot tutorial.

Overview

Requirements:

Kinetic
$ sudo apt-get install ros-kinetic-turtlebot-bringup ros-kinetic-turtlebot-navigation ros-kinetic-rtabmap-ros

Indigo
$ sudo apt-get install ros-indigo-turtlebot-bringup ros-indigo-turtlebot-navigation ros-indigo-rtabmap-ros

Turtlebot mapping with rtabmap

Usage:

 $ roslaunch turtlebot_bringup minimal.launch
 $ roslaunch rtabmap_ros demo_turtlebot_mapping.launch

Visualization (turtlebot_navigation.rviz):

 $ roslaunch rtabmap_ros demo_turtlebot_rviz.launch
or
 $ rosrun rviz rviz -d turtlebot_navigation.rviz

You should see a 2D map and a 3D map. For the navigation stuff, see below. By default, rtabmap re-uses always the same database after each mapping session. To delete the old one and start fresh, delete the database saved here ~/.ros/rtabmap.db or use argument args:="--delete_db_on_start" when launching the demo_turtlebot_mapping.launch:

 $ roslaunch rtabmap_ros demo_turtlebot_mapping.launch args:="--delete_db_on_start"

Localization mode

After a mapping session as above, a database is saved here ~/.ros/rtabmap.db. Now restart the demo_turtlebot_mapping.launch with argument localization:=true:

 $ roslaunch rtabmap_ros demo_turtlebot_mapping.launch localization:=true

Move the robot around until it can relocalize in the previous map, then the 2D map would re-appear again when a loop closure is found.

Autonomous Navigation

When a map is created (in mapping mode or localization mode), you can then follow the same steps from 2.3.2 of the Autonomous Navigation of a Known Map with TurtleBot tutorial to navigate in the map.

Normally, you only have to "drop" a navigation goal on the map with RVIZ to see the robot moving autonomously to it. Click on "2D Nav Goal" button in RVIZ to set a goal. You should see a planned path (red line) like this to the goal set (green arrow):

Turtlebot navigation with rtabmap

The commands sent by move_base:

$ rostopic echo /mobile_base/commands/velocity

Freenect/OpenNI2 on Indigo

By default, OpenNI2 is used from the included 3dsensor.launch (TURTLEBOT_3D_SENSOR=asus_xtion_pro). If you want to use Freenect driver, set this before launching demo_turtlebot_mapping.launch:

$ export TURTLEBOT_3D_SENSOR=kinect

If you don't have the robot

If you don't have the robot and you just want to see what it could look like if you have one, you can still generate an odometry like this (with rgbd_odometry:=true):

$ roslaunch turtlebot_bringup minimal.launch
$ roslaunch rtabmap_ros demo_turtlebot_mapping.launch args:="--delete_db_on_start" rgbd_odometry:=true
$ roslaunch rtabmap_ros demo_turtlebot_rviz.launch

Simulation (Gazebo)

Note This example has been added on August 2017, make sure you have the demo_turtlebot_mapping.launch with simulation argument depending on the rtabmap_ros version installed.

$ roslaunch turtlebot_gazebo turtlebot_world.launch
$ roslaunch rtabmap_ros demo_turtlebot_mapping.launch simulation:=true
$ roslaunch rtabmap_ros demo_turtlebot_rviz.launch
  • Verify that /scan topic is published after launching turtlebot_world.launch. If not, edit turtlebot_world.launch and use depthimage_to_laserscan node instead of the nodelet:

    • $ sudo gedit /opt/ros/indigo/share/turtlebot_gazebo/launch/turtlebot_world.launch
      
      <!-- Fake laser -->
      <node pkg="depthimage_to_laserscan" type="depthimage_to_laserscan" name="depthimage_to_laserscan">
          <param name="scan_height" value="10"/>
          <param name="output_frame_id" value="/camera_depth_frame"/>
          <param name="range_min" value="0.45"/>
          <remap from="image" to="/camera/depth/image_raw"/>
          <remap from="scan" to="/scan"/>
      </node>
  • If when sending goals, Turtlebot is always turning (overshooting rotation), set max_vel_x to 0.3 and sim_time to 1.3. You can also set allow_unknown to be able to send goals in unknown areas of the map.

Turtlebot3 on Melodic and Noetic

Note This example has been added on September 2019, the following file may not be installed with binaries, download it here: demo_turtlebot3_navigation.launch

Install:

# Melodic:
sudo apt install ros-melodic-turtlebot3-simulations ros-melodic-turtlebot3-navigation ros-melodic-dwa-local-planner

# Noetic:
sudo apt install ros-noetic-turtlebot3-simulations ros-noetic-turtlebot3-navigation ros-noetic-dwa-local-planner 

Launch:

 $ export TURTLEBOT3_MODEL=waffle
 $ roslaunch turtlebot3_gazebo turtlebot3_world.launch

 $ export TURTLEBOT3_MODEL=waffle
 $ roslaunch rtabmap_ros demo_turtlebot3_navigation.launch

To avoid TF warning about leading '/' in frame name (map, odom, base_footprint), remove it in those files:

  • /opt/ros/melodic/share/turtlebot3_navigation/param/global_costmap_params.yaml

  • /opt/ros/melodic/share/turtlebot3_navigation/param/local_costmap_params.yaml

Issues

  • On autonomous navigation, if teleop node is also sending commands on the same topic as move_base at the same time, the robot may not move.

  • If there are many TF warnings, you can try to increase robot_state_publisher's publishing frequency in turtlebot_bringup/launch/includes/robot.launch.xml from 5 to 10 Hz. You can also increase wait_for_transform argument of demo_turtlebot_mapping.launch to 0.2.

  • If sometimes the robot is planning a straight path through an obstacle, it may be related to this issue. This can be fixed by using rtabmap_ros::StaticLayer instead of costmap_2d::StaticLayer here.

Wiki: rtabmap_ros/TutorialsOldInterface/MappingAndNavigationOnTurtlebot (last edited 2023-04-19 04:41:21 by MathieuLabbe)