Revision 113 as of 2017-07-28 21:25:59

Clear message

  Show EOL distros: 

Not supported

Introduction

"rrt_exploration" is a ROS package that implements a multi-robot map exploration algorithm for mobile robots. It is based on the Rapidly-Exploring Random Tree (RRT) algorithm. It uses occupancy girds as a map representation.The package has 5 different ROS nodes:

  • Global RRT frontier point detector node.
  • Local RRT frontier point detector node.
  • OpenCV-based frontier detector node.
  • Filter node.
  • Assigner node.

The video below shows the package running on Gazebo simulation of three robots:

This video below shows the package running on real robots:

The package works for a single robot as well.

Package Requirements

The package has been tested on both ROS Kinetic and ROS Indigo, it should work on other distributions like Jade. The following requirements are needed before installing the package:

1- You should have installed a ROS distribution (indigo or later. Recommended is either indigo or kinetic).

2- Created a workspace.

3- Installed the "gmapping" ROS package, you can do that by typing the following command in the terminal:

sudo apt-get install ros-$ROS_DISTRO-gmapping

4- Install ROS navigation stack. You can do that with the following command:

sudo apt-get install ros-$ROS_DISTRO-navigation

5- You should have Python 2.7. (it was not tested on Python 3).

6-You should have/install the following python modules:

-OpenCV (cv2)

sudo apt-get install python-opencv

-Numpy

sudo apt-get install python-numpy

-Sklearn

sudo apt-get install python-scikits-learn

Hardware Requirements

A mobile robot that can be used with the navigation stack (publishes /odom and /tf. Receives velocity commands ..). The robot must also be equipped with a laser scanner or any sensor that publishes laser scan message (sensor_msgs/LaserScan).

Installation

Download the package and place it inside the /src folder in your workspace. And then compile using catkin_make.

Setting Up Your Robots

This package provides an exploration strategy for single or multiple robots. However, for it to work, you should have set your robots ready using the navigation stack. And each robot should run the "slam_gmapping" node from the gmapping package.

Additionally, the robots must be set and prepared as follows.

Note: If you want to quickly run and test the package, you can try out the rrt_exploration_tutorials package which provides Gazebo simulation for single and multiple robots, you can use it to directly with this package.

Robots Network

For the multi-robot configuration, the package doesn't require special network configuration, it simply works by having a single ROS master (can be one of the robots). So on the other robots, the ROS_MASTER_URI parameter should be pointing at the master's address. For more information on setting up ROS on multiple machines, follow this link.

Robot's frame names in tf

All robot's frames should be prefixed by its name. Naming of robots starts from "/robot_1", "/robot_2", "/robot_3", .. and so on. Even if you are using the package for single robot, robot's frames should be prefixed by its name (i.e. /robot_1). So for robot_1, the frames in the tf tree should look like this:

https://github.com/hasauino/storage/blob/master/pictures/framesTf.png?raw=true

Robot's node and topic names

All the nodes and topics running on a robot must also be prefixed by its name. For robot 1, node names should look like: /robot_1/move_base_node, /robot_1/slam_gmapping.

And topic names should be like: /robot_1/odom, /robot_1/map, /robot_1/base_scan, ..etc.

Setting up the navigation stack on the robots

The move_base_node node, which brings up the navigation stack on the robot, must be running. This package (rrt_exploration) generates target exploration goals, each robot must be able to receive these points and move towards them. This is why the navigation stack is needed. Additionally, each robot must have a global and local cost maps. All of these are proivded from the move_base_node.

A mapping node

Each robot should have a local map generated from the gmapping package.

A map merging node

For the multi-robot case, there should be a node that merges all the local maps into one global map. You can use this package.

Nodes

There are 3 types of nodes; nodes for detecting frontier points in an occupancy grid map, a node for filtering the detected points, and a node for assigning the points to the robots. The following figure shows the structure:

https://github.com/hasauino/storage/blob/master/pictures/fullSchematic.png?raw=true

global_rrt_frontier_detector

The global_rrt_frontier_detector node takes an occupancy grid and finds frontier points (which are exploration targets) in it. It publishes the detected points so the filter node can process. In multi-robot configuration, it is intended to have only a single instance of this node running.
Running additional instances of the global frontier detector can enhance the speed of frontier points detection, if needed.

Subscribed Topics

map (nav_msgs/OccupancyGrid)
  • Topic name is defined by the ~map_topic parameter. It is the topic name on which the node will receive the map.
clicked_point (geometry_msgs/PointStamped)
  • The global_rrt_frontier_detector node requires that the region to be explored is defined. This topic is where the node recieves five points that define the region. The first four points are four defining a square region to be explored, and the last point is the tree starting point. After publishing those five points on this topic, the RRT will start detecting frontier points. The five points are intended to be published from Rviz using https://github.com/hasauino/storage/blob/master/pictures/publishPointRviz_button.png?raw=true button.

Published Topics

detected_points (geometry_msgs/PointStamped)
  • The topic on which the node publishes detected frontier points.

Parameters

~map_topic (string, default: "/robot_1/map")
  • This parameter defines the topic name on which the node will receive the map.
~eta (float, default: 0.5)
  • This parameter controls the growth rate of the RRT that is used in the detection of frontier points, the unit is in meters. This parameter should be set according to the map size, a very large value will cause the tree to grow faster and hence detect frontier points faster, but a large growth rate also implies that the tree will be missing small corners in the map.

local_rrt_frontier_detector

This node is similar to the global_rrt_frontier_detector. However, it works differently, as the tree here keeps resetting every time a frontier point is detected. This node is intended to be run along side the global_rrt_frontier_detector node, it is responsible for fast detection of frontier points that lie in the close vicinity of the robot.
In multi-robot configuration, each robot runs an instance of the local_rrt_frontier_detector. So for a team of 3 robots, there will be 4 nodes for detecting frontier points; 3 local detectors and 1 global detector. Running additional instances of the local frontier detector can enhance the speed of frontier points detection, if needed.
All detectors will be publishing detected frontier points on the same topic ("/detected_points").

Subscribed Topics

map (nav_msgs/OccupancyGrid)
  • Topic name is defined by the ~map_topic parameter. It is the topic name on which the node will receive the map.
clicked_point (geometry_msgs/PointStamped)
  • The global_rrt_frontier_detector node requires that the region to be explored is defined. This topic is where the node recieves five points that define the region. The first four points are four defining a square region to be explored, and the last point is the tree starting point. After publishing those five points on this topic, the RRT will start detecting frontier points. The five points are intended to be published from Rviz using https://github.com/hasauino/storage/blob/master/pictures/publishPointRviz_button.png?raw=true button.

Published Topics

detected_points (geometry_msgs/PointStamped)
  • The topic on which the node publishes detected frontier points.

Parameters

~/robot_1/base_link (string, default: "/robot_1/base_link")
  • The frame attached to the robot. Every time the tree resets, it will start from the current robot location obtained from this frame.
~map_topic (string, default: 0.5)
  • This parameter defines the topic name on which the node will receive the map.
~eta (float)
  • This parameter controls the growth rate of the RRT that is used in the detection of frontier points, the unit is in meters. This parameter should be set according to the map size, a very large value will cause the tree to grow faster and hence detect frontier points faster, but a large growth rate also implies that the tree will be missing small corners in the map.