SLAM Toolbox¶
Introduction¶
This tutorial explains how to use the ROS tool **Slam Toolbox ** for mapping and localization. This SLAM library is introduced as follows: “This project contains the ability to do most everything any other available SLAM library, both free and paid, and more.” This is a statement, because there are dozens of different SLAMs available.
So like every other SLAM, its main task is to build a map of the environment and simultaneously estimates the robots pose in 2D space.
Lines beginning with $ are terminal commands.
To open a new terminal use the shortcut Ctrl + Alt + T.
To open a new tab inside an existing terminal use the shortcut Ctrl + Shift + T.
To kill a process in a terminal use the shortcut Ctrl + C.
Lines beginning with # indicate the syntax of the commands.
Code is separated in boxes.
Code is case sensitive.
General Approach¶
SLAM Toolbox is a configurable SLAM (Simultaneous Localization And Mapping) approach. It offers:
continuing to refine, remap or continue saved graphs at any time.
life-long mapping: load a saved graph and continue mapping and
remove extraneaous information from newly added scans
an optimization-based localization mode
kinematic map merging
lossless data storage
and a a lot more…
For further details check: https://github.com/SteveMacenski/slam_toolbox
Install¶
To install Slam Toolbox for ROS2 follow these instructions:
$ cd ~/turtlebot3_ws/src
$ git clone https://github.com/SteveMacenski/slam_toolbox
$ cd ..
$ rosdep install -q -y -r --from-paths src --ignore-src
$ colcon build
The installation of the requirements and the build process itself might take a while, as this is a very large project.
Build a Map With Slam Toolbox¶
Create a new package called my_robot_slam.
In this package create a launch file slam_toolbox.launch.py
:
from launch import LaunchDescription
import launch_ros.actions
from ament_index_python.packages import get_package_share_directory
def generate_launch_description():
return LaunchDescription([
launch_ros.actions.Node(
parameters=[
get_package_share_directory("my_robot_slam") + '/config/map_params.yaml'
],
package='slam_toolbox',
node_executable='sync_slam_toolbox_node',
name='slam_toolbox',
output='screen'
)
])
Now create the config .yaml file, which is inluced in that launch file map_params.yaml. Put it in a directory in your package named config
This file includes all parameters to adjust the SLAM.
For further information regarding the different parameters, take a look at https://github.com/SteveMacenski/slam_toolbox#configuration.
To test Slam Toolbox:
Start your Gazebo simulation with a Turtlebot3.
Start a Node to be able to teleoperate your robot.
Run rviz2 and visualize the /map topic.
Set the depth of the /map topic in rviz to 1
and the QoS policies to System Default
Start Slam Toolbox:
$ ros2 launch my_robot_slam slam_toolbox.launch.py
Now move your robot around and create a map of your environment.
If you’re done and happy with the created map, save it:
$ ros2 service call /save_map slam_toolbox/srv/SaveMap
This will save an image of the map and the pose-graph to your current directory.