Skip to main content
Version: ROS 2 Humble

SLAM

Simultaneous localization and mapping (SLAM) is a method of generating a map and tracking the robot's location within the map. It is generally done using laser scan data from a 2D LIDAR, and the robot's odometry. For this demo we are using the slam_toolbox package to map our environment. This tutorial will use the Clearpath simulator, but will work on a physical robot too. We will be using a J100 with a Hokuyo UST10 attached to the front of the robot.

J100 YAML

serial_number: j100-0001
version: 0
system:
username: administrator
hosts:
- hostname: cpr-j100-0001
ip: 192.168.131.1
ros2:
namespace: j100_0001
domain_id: 0
middleware:
implementation: rmw_fastrtps_cpp
extras:
ros_parameters:
linear.x.max_velocity": 2.0
linear.x.min_velocity": -2.0
linear.x.max_acceleration": 20.0
linear.x.min_acceleration": -20.0
angular.z.max_velocity": 4.0
angular.z.min_velocity": -4.0
angular.z.max_acceleration": 25.0
angular.z.min_acceleration": -25.0
platform:
controller: ps4
decorations:
front_bumper:
enabled: true
model: default
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
extension: 0.0
rear_bumper:
enabled: true
model: default
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
extension: 0.0
top_plate:
enabled: true
model: default
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
sensors:
lidar2d:
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: front_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
urg_node:
angle_min: -1.5707
angle_max: 1.5707

tip

Make sure you have installed the simulator before starting this tutorial. Take a look at the installation guide for details.

Launching the simulation and SLAM

1. Move the robot.yaml file to your setup folder ($HOME/clearpath by default).

2. Launch the simulation

ros2 launch clearpath_gz simulation.launch.py

Click on the orange play button in the bottom left corner to start the simulation.

3. In another terminal, launch RViz

ros2 launch clearpath_viz view_navigation.launch.py namespace:=j100_0001

4. In another terminal, launch SLAM

ros2 launch clearpath_nav2_demos slam.launch.py setup_path:=$HOME/clearpath/ use_sim_time:=true

5. Drive the robot around the world until the entire map has been generated

SLAM in simulation

6. Save the map

ros2 run nav2_map_server map_saver_cli -f "map_name" \
--ros-args -p map_subscribe_transient_local:=true -r __ns:=/j100_0001