Skip to main content

Exploration

Chapter description

We are nearing the end of our adventures with navigation in ROS. The last task will be exploring the surroundings with the ROSbot. To complete this exercise, it is necessary to learn about gmapping and move_base from the tutorials 8. SLAM and 9. Navigation.

You can run this tutorial on:

Repository containing the final effect after doing all the ROS Tutorials you can find here

Introduction

Exploration is about gathering information about an unfamiliar environment as quickly as possible. For this purpose, the explore_lite package will be used, which contains a node named explore. Alg, which determines the desired positions of the robot in such a way as to provide as much information about the environment as possible. The node is based on the occupancy map, on which it selects the point that it believes will allow to collect the most information about the environment. This point is implemented by any algorithm from the move_base package, which causes the robot to move to an unexplored area. When the selected point is reached, the slam algorithm will create a map and classify that area as free or occupied. Then a new point is set and the map boundaries are moved. The process is repeated until all boundaries have been explored, which means the area must be surrounded. Otherwise, the robot will never finish exploring the environment.

Requirements regarding robot

Before continuing with explore_lite node certain requirements must be met, robot should:

  • subscribe /move_base/goal topic with message type geometry_msgs/PoseStamped in which robot desired positions are included.
  • Publish map to /map topic with message type nav_msgs/OccupancyGrid

Above configuration is met by the robot created in previous tutorials. To install explore lite simply type the command below into the terminal:

husarion@husarion:~$
sudo apt install ros-$ROS_DISTRO-explore-lite

Configuration of explore node

As in previous cases, using a new package requires proper configuration. According to the approach learned in the previous tutorial, let's create a separate configuration file named exploration.yaml in the tutorial_pkg/config directory. Your file should contain the following parameters:

~/ros_ws/src/tutorial_pkg/config/exploration.yaml
robot_base_frame: base_link
costmap_topic: map
costmap_updates_topic: map_updates
visualize: true
planner_frequency: 0.4
progress_timeout: 30.0
potential_scale: 3.0
orientation_scale: 0.0
gain_scale: 1.0
transform_tolerance: 0.3
min_frontier_size: 0.7

The code explained

  • 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

To test the above configuration, you need to run the explore_lite node along with the necessary nodes such as:

  • ROSbot/Gazebo - turn on the robot, calculate odometry, and publish and subscribe all necessary to move the robot,
  • rplidarNode - driver for rpLidar laser scanner,
  • slam_gmapping - locating a robot and building a map of node,
  • move_base - trajectory planner,
  • explore_lite - exploration task,
  • rviz - visualization tool.

The entire explore.launch file should look like this:

~/ros_ws/src/tutorial_pkg/launch/explore.launch
<launch>

<arg name="use_gazebo" default="false" />

<!-- Gazebo -->
<group if="$(arg use_gazebo)">
<param name="use_sim_time" value="true" />
<include file="$(find rosbot_bringup)/launch/rosbot_tutorial.launch">
<arg name="world" value="maze" />
</include>
</group>

<!-- SLAM -->
<node pkg="gmapping" type="slam_gmapping" name="gmapping_node" output="log">
<param name="base_frame" value="base_link"/>
<param name="odom_frame" value="odom" />
<param name="map_update_interval" value="1.5"/>
<param name="maxUrange" value="15.0"/>
<param name="delta" value="0.03" />
<param name="xmin" value="-10" />
<param name="ymin" value="-10" />
<param name="xmax" value="10" />
<param name="ymax" value="10" />
</node>

<!-- Path planning -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find tutorial_pkg)/config/move_base.yaml" command="load" />
<rosparam file="$(find tutorial_pkg)/config/costmap_common.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find tutorial_pkg)/config/costmap_common.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find tutorial_pkg)/config/costmap_global.yaml" command="load" />
<rosparam file="$(find tutorial_pkg)/config/costmap_local.yaml" command="load" />
<rosparam file="$(find tutorial_pkg)/config/planner_global.yaml" command="load" />
<rosparam file="$(find tutorial_pkg)/config/planner_local.yaml" command="load" />
</node>

<!-- Explore -->
<node pkg="explore_lite" type="explore" respawn="true" name="explore" output="screen">
<rosparam file="$(find tutorial_pkg)/config/exploration.yaml" command="load" />
</node>

<!-- RViz -->
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find tutorial_pkg)/rviz/explore.rviz"/>

</launch>

Let's explore

Before we run explore.launch, we have configured RViz for you. You can download this RViz configuration from repo explore.rviz. Name the file as explore.rviz and place it in the tutorial_pkg/rviz directory. Now we are ready to launch our program. Launch this with commands:

husarion@husarion:~$
docker compose up -d rosbot ros-master rplidar
roslaunch tutorial_pkg explore.launch

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 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 Adam Krawczyk, 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 with our support: support@husarion.com