Mapping with SLAM Toolbox and EasyNavο
This HowTo shows how to perform mapping and navigation with SLAM Toolbox and EasyNavigation (EasyNav). It assumes that the environment has already been mapped and that you will now configure and run EasyNav to navigate using the generated map.
Setupο
Before starting, ensure that:
You have completed the installation steps in Build & Install.
You have cloned and built the following repositories in your workspace:
EasyNavigationeasynav_pluginseasynav_playground_kobuki(for simulation)easynav_indoor_testcase(for maps and parameter examples)
Your workspace is sourced:
cd ~/ros/ros2/easynav_ws source install/setup.bash
β
Mapping and Preparationο
If you have not yet created a map, follow the steps in Mapping with the Costmap Stack.
Once the environment is mapped, save the resulting map files (YAML + image) in the directory of any package
in your workspace β for example, inside easynav_indoor_testcase/maps.
You can later reference this map using the parameters package and map_path_file in your configuration file.
(Alternatively, you may use an absolute path with map_path_file alone.)
β
Creating a Parameter Fileο
In this example, we will use:
The SeReST controller for motion control.
The AMCL localizer for probabilistic localization.
The Simple Maps Manager to load the map representation.
Below is a minimal configuration that allows a simulated robot to navigate in a mapped environment.
controller_node:
ros__parameters:
use_sim_time: true
controller_types: [serest]
serest:
rt_freq: 30.0
plugin: easynav_serest_controller/SerestController
allow_reverse: true
max_linear_speed: 0.8
max_angular_speed: 1.2
v_progress_min: 0.08
k_s_share_max: 0.5
k_theta: 2.5
k_y: 1.5
goal_pos_tol: 0.1
goal_yaw_tol_deg: 6.0
slow_radius: 0.80
slow_min_speed: 0.02
final_align_k: 2.5
final_align_wmax: 0.8
corner_guard_enable: true
corner_gain_ey: 1.8
corner_gain_eth: 0.7
corner_gain_kappa: 0.4
corner_min_alpha: 0.35
corner_boost_omega: 1.0
a_lat_soft: 0.9
apex_ey_des: 0.05
localizer_node:
ros__parameters:
use_sim_time: true
localizer_types: [simple]
simple:
rt_freq: 50.0
freq: 5.0
reseed_freq: 1.0
plugin: easynav_simple_localizer/AMCLLocalizer
num_particles: 100
noise_translation: 0.05
noise_rotation: 0.1
noise_translation_to_rotation: 0.1
initial_pose:
x: 0.0
y: 0.0
yaw: 0.0
std_dev_xy: 0.1
std_dev_yaw: 0.01
maps_manager_node:
ros__parameters:
use_sim_time: true
map_types: [simple]
simple:
freq: 10.0
plugin: easynav_simple_maps_manager/SimpleMapsManager
package: easynav_indoor_testcase
map_path_file: maps/home.yaml
planner_node:
ros__parameters:
use_sim_time: true
planner_types: [simple]
simple:
freq: 0.5
plugin: easynav_simple_planner/SimplePlanner
robot_radius: 0.25
sensors_node:
ros__parameters:
use_sim_time: true
forget_time: 0.5
sensors: [laser1]
perception_default_frame: odom
laser1:
topic: scan_raw
type: sensor_msgs/msg/LaserScan
group: points
system_node:
ros__parameters:
use_sim_time: true
position_tolerance: 0.3
angle_tolerance: 0.15
β
Running the Simulationο
Launch the simulator. You can disable the Gazebo GUI to save resources:
ros2 launch easynav_playground_kobuki playground_kobuki.launch.py gui:=false
Launch RViz2 in a new terminal:
ros2 run rviz2 rviz2 --ros-args -p use_sim_time:=true
Start EasyNav using your parameter file:
ros2 run easynav_system system_main \ --ros-args --params-file ~/ros/ros2/easynav_ws/src/easynav_indoor_testcase/robots_params/simple.serest_params.yaml
(You can also create a dedicated launcher file for convenience.)
In RViz2, use the β2D Goal Poseβ tool to send navigation goals. The robot should begin navigating autonomously along collision-free paths.
β
Notesο
Ensure that the
map_path_filepath and package name correspond to your actual map.The Simple Stack is suitable for 2D navigation with binary occupancy grids; for graded cost-based navigation, consider switching to the Costmap Stack (Mapping with the Costmap Stack).
If navigation oscillates or stalls, verify that the controller gains (
k_theta,k_y) and speed limits are consistent with your robotβs maximum velocities.