Skip to main content

Exploration

We are nearing the end of our adventures with navigation in ROS 2, but the most exciting part is yet to come - the exploration of our surroundings with the ROSbot. To complete this exercise, it is necessary to learn about slam_toolbox and nav2 from the tutorials 8. SLAM and 9. Path planning.

ros2 exploration tutorial

Prerequisites

This tutorial is dedicated to the ROSbot XL equipped with any Slamtec LiDAR. However, most of the information and commands are also compatible with ROSbot 2R/2 PRO, and most changes are simple and come down to launching the appropriate container, depending on your hardware configuration. It is also possible to solve the tutorial using the Gazebo simulation.

info

If you don't already own a ROSbot, you can get one from the Husarion store.

The tutorials are designed to flow sequentially and are best followed in order. If you're looking to quickly assess the content of a specific tutorial, refer to the ROS 2 Tutorials repository, which contains the completed outcomes.

Introduction

Exploration is about gathering information about an unfamiliar environment as quickly as possible. For this purpose, the explore_lite package from github. An algorithm that controls the robot in such a way as to provide as much information about the environment as possible. The node relies on the occupancy map generated by slam_toolbox, on the basis of which it selects a point to discover an unexplored area. After reaching the selected point, the map algorithm is expanded and the robot heads to the next point. This process is repeated until all boundaries have been explored. Therefore, you must move in a closed space, otherwise the robot will never finish exploring the environment.

Install explore-lite

To clone package form github use bellow command:

husarion@husarion:~/ros2_ws/src$
git clone https://github.com/robo-friends/m-explore-ros2.git

and build new package:

husarion@husarion:~/ros2_ws$
colcon build --symlink-install

Configuration of explore node

As in the previous cases, download explor_lite configuration file from github and add it to the config folder under the name explore.yaml. This file largely resembles the configuration of navigation.yaml, which is due to the fact that, apart from this tutorial, we also use the nav2 package. This file differs mainly in dropping the parameters for amcl and map_server and adding parameters for the explor_lite package. Your file additionally contains the following parameters:

~/ros2_ws/src/tutorial_pkg/config/explore.yaml
explore_node:
ros__parameters:
robot_base_frame: base_link
costmap_topic: /global_costmap/costmap
costmap_updates_topic: /global_costmap/costmap_updates
visualize: false
planner_frequency: 0.2
progress_timeout: 15.0
potential_scale: 5.0
orientation_scale: 0.5
gain_scale: 1.0
transform_tolerance: 0.1
min_frontier_size: 0.6
Explanation of the parameters
  • robot_base_frame - the name of the base frame of the robot. This is used for determining robot position on map.
  • costmap_topic - Specifies topic of source nav_msgs/OccupancyGrid.
  • costmap_updates_topic - Specifies topic of source map_msgs/OccupancyGridUpdate. Not necessary if source of map is always publishing full updates, i.e. does not provide this topic.
  • visualize - Specifies whether or not publish visualized frontiers.
  • planner_frequency - Rate in Hz at which new frontiers will computed and goal reconsidered.
  • progress_timeout - Time in seconds when robot do not make any progress for progress_timeout, current goal will be abandoned.
  • potential_scale - Used for weighting frontiers. This multiplicative parameter affects frontier potential component of the frontier weight (distance to frontier).
  • orientation_scale - Used for weighting frontiers. This multiplicative parameter affects frontier orientation component of the frontier weight.
  • gain_scale - Used for weighting frontiers. This multiplicative parameter affects frontier gain component of the frontier weight (frontier size).
  • transform_tolerance - Transform tolerance to use when transforming robot pose.
  • min_frontier_size - Minimum size of the frontier to consider the frontier as the exploration goal. Value is in meter.

Launching exploration task

Next, let's create an explore.launch.py file that will run:

  • slam_toolbox - locate the robot and build a map,
  • nav2 - robot navigation,
  • explore_lite - exploration algorithm,
  • rviz2 - visualization tool.

The entire explore.launch.py file should look like this:

~/ros2_ws/src/tutorial_pkg/launch/explore.launch.py
import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node


def generate_launch_description():
tutorial_dir = get_package_share_directory('tutorial_pkg')
nav2_bringup_dir = get_package_share_directory('nav2_bringup')
explore_lite_launch = os.path.join(
get_package_share_directory('explore_lite'), 'launch', 'explore.launch.py'
)

params_file = LaunchConfiguration('params_file')
use_sim_time = LaunchConfiguration('use_sim_time')

declare_params_file_cmd = DeclareLaunchArgument(
'params_file',
default_value=os.path.join(tutorial_dir, 'config', 'explore.yaml'),
description='Full path to the ROS2 parameters file to use for all launched nodes',
)

declare_use_sim_time_cmd = DeclareLaunchArgument(
'use_sim_time', default_value='false', description='Use simulation (Gazebo) clock if true'
)

slam_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(tutorial_dir, 'launch', 'slam.launch.py')),
launch_arguments={
'use_sim_time': use_sim_time,
'use_rviz': 'false'
}.items(),
)

nav2_bringup_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(nav2_bringup_dir, 'launch', 'navigation_launch.py')),
launch_arguments={
'use_sim_time': use_sim_time,
'params_file': params_file,
}.items(),
)

explore_lite_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource([explore_lite_launch]),
launch_arguments={
'use_sim_time': use_sim_time,
}.items(),
)

rviz_config_dir = os.path.join(
tutorial_dir,
'rviz',
'explore.rviz',
)

rviz_node = Node(
package='rviz2',
executable='rviz2',
name='rviz2',
arguments=['-d', rviz_config_dir],
parameters=[{'use_sim_time': use_sim_time}],
output='screen',
)

ld = LaunchDescription()

ld.add_action(declare_params_file_cmd)
ld.add_action(declare_use_sim_time_cmd)

ld.add_action(slam_launch)
ld.add_action(nav2_bringup_launch)
ld.add_action(explore_lite_launch)
ld.add_action(rviz_node)

return ld

Before we run explore.launch.py, download RViz configuration. Name the file explore.rviz, place it in the tutorial_pkg/rviz directory and build the package again. Now you are ready to run the program.

Let's explore

On ROSbot

Run the ROSbot:

husarion@husarion:~$
docker compose up -d microros <rosbot_service> rplidar
How to add RPlidar to your configuration?

You can add rplidar service to your compose.yaml by placing following code at the end of file.

rplidar:
image: husarion/rplidar:humble
<<: *net-config
devices:
- /dev/ttyRPLIDAR:/dev/ttyUSB0
command: ros2 launch sllidar_ros2 sllidar_launch.py serial_baudrate:=${LIDAR_BAUDRATE:-115200}

Depend on your ROSbot model, you should use appropriate name for your <rosbot_service>. To check available docker service use following command docker compose config --services, or find suitable Docker images prepared by Husarion.

Then in the new terminal run explore.launch.py.

husarion@husarion:~$
ros2 launch tutorial_pkg explore.launch.py

If everything was set correctly exploration will start immediately after node initialization. Exploration will finish when whole area is discovered. An example result might look like this:

image

Summary

Congratulations, you have completed all ROS 2 tutorials! 🎉

I hope you enjoyed learning ROS and learned a lot of practical things. We believe that after completing all these courses, controlling and navigating the robot has become much easier for you, and after completing today's exercise, you can make your ROSbot patrol the surroundings using the explore_lite package.


by Rafał Górecki, Husarion

Do you need any support with completing this tutorial or have any difficulties with software or hardware? Feel free to describe your thoughts on our community forum: https://community.husarion.com/ or to contact our support: support@husarion.com