Wiki

Only released in EOL distros:  

Package Summary

A ROS package that implements a multi-robot RRT-based map exploration algorithm. It also has the image-based frontier detection that uses image processing to extract frontier points

Package Summary

A ROS package that implements a multi-robot RRT-based map exploration algorithm. It also has the image-based frontier detection that uses image processing to extract frontier points

/!\ If you are using this package in your research work, please cite these papers:

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 grids as a map representation.The package has 5 different ROS nodes:

This is a playlist showing the package running on real robots and on Gazebo simulation:

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 directly with this package.

Single Robot Setup

If you are using this package for exploration using a single robot, then you will first need the following:

Setting up the navigation stack on the robot

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

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

Multiple Robots Setup

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. 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

There should be a node that merges all the local maps into one global map. You can use the "multirobot_map_merge" package developed by Jiri Horner.

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) clicked_point (geometry_msgs/PointStamped)

Published Topics

detected_points (geometry_msgs/PointStamped) ~shapes (visualization_msgs/Marker)

Parameters

~map_topic (string, default: "/robot_1/map") ~eta (float, default: 0.5)

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) clicked_point (geometry_msgs/PointStamped)

Published Topics

detected_points (geometry_msgs/PointStamped) ~shapes (visualization_msgs/Marker)

Parameters

~/robot_1/base_link (string, default: "/robot_1/base_link") ~map_topic (string, default: 0.5) ~eta (float)

frontier_opencv_detector

This node is another frontier detector, but it is not based on RRT. This node uses OpenCV tools to detect frontier points. It is intended to be run alone, and in multi-robot configuration only one instance should be run (running additional instances of this node does not make any difference).
Originally this node was implemented for comparison against the RRT-based frontier detectors. Running this node along side the RRT detectors (local and global) may enhance the speed of frotiner points detection.
Note: You can run any type and any number of detectors, all the detectors will be publishing on the same topic which the filter node (will be explained in the following section) is subscribing to. on the other hand, the filter will pass the filtered forntier points to the assigner in order to command the robots to explore these points.

Subscribed Topics

map (nav_msgs/OccupancyGrid)

Published Topics

detected_points (geometry_msgs/PointStamped) shapes (visualization_msgs/Marker)

Parameters

~map_topic (string, default: "/robot_1/map")

filter

The filter nodes receives the detected frontier points from all the detectors, filters the points, and passes them to the assigner node to command the robots. Filtration includes the delection of old and invalid points, and it also dicards redundant points.

Subscribed Topics

map (nav_msgs/OccupancyGrid) robot_x/move_base_node/global_costmap/costmap (nav_msgs/OccupancyGrid) The goals topic (geometry_msgs/PointStamped)

Published Topics

frontiers (visualization_msgs/Marker) centroids (visualization_msgs/Marker) filtered_points (invalid message type for MsgLink(msg/type))

Parameters

~map_topic (string, default: "/robot_1/map") ~costmap_clearing_threshold (float, default: 70.0) ~info_radius (float, default: 1.0) ~goals_topic (string, default: "/detected_points") ~n_robots (float, default: 1.0) ~namespace (string, default: )
  • namespace used in prefixing robot tf frame names and topic names . Normally, it's an empty string for the single robot case. However, in the multi-robot case, robot names (their tf frames and topic names) should be prefixed with a namespace (as described earlier). For example, if you have three robots with the following namespaces: "/robot_1","/robot_2", and "/robot_3", then you have to set this parameter to "/robot_"
~namespace_init_count (float, default: 1.0)
  • Starting index for robot names, this index follows the namespace described above. It is used only for the multi-robot case (for the single robot case, this parameter is not used and can be neglected). In the multi-robot case, robot names have a namespace (you can set using the previously mentioned parameter), and followed by an index. If your set up has robot names that do not start with 1, then you can use this parameter according to you set up. Example: suppose you have two robots with the namespaces "/robot_4" and "/robot_5", then you have to set this parameter to 4.
~rate (float, default: 100.0)
  • node loop rate (in Hz).

Assigner

This node recieve target exploration goals, which are the filtered frontier points published by the filter node, and commands the robots accordingly. The assigner node commands the robots through the move_base_node. This is why you have bring up the navigation stack on your robots.

Subscribed Topics

map (nav_msgs/OccupancyGrid)
  • Topic name is defined by the ~map_topic parameter.
Filtered frontier points topic (nav_msgs/OccupancyGrid)
  • Topic name is defined by the ~frontiers_topic parameter
The goals topic (invalid message type for MsgLink(msg/type))
  • Topic name is defined by the ~goals_topic parameter. It's the topic on which the filter node receives detected frontier points.

Parameters

~map_topic (string, default: "/robot_1/map")
  • This parameter defines the topic name on which the node will recieve the map. In the single robot case, this topic should be set to the map topic of the robot. In the multi-robot case, this topic must be set to global merged map.
~info_radius (float, default: 1.0)
  • The information radius used in calculating the information gain of frontier points.
~info_multiplier (float, default: 3.0)
  • The unit is meter. This parameter is used to give importance to information gain of a frontier point over the cost (expected travel distance to a frontier point).
~hysteresis_radius (float, default: 3.0)
  • The unit is meter. This parameter defines the hysteresis radius.
~hysteresis_gain (float, default: 2.0)
  • The unit is meter. This parameter defines the hysteresis gain.
~frontiers_topic (string, default: "/filtered_points")
  • The topic on which the assigner node receives filtered frontier points.
~n_robots (float, default: 1.0)
  • Number of robots.
~namespace (string, default: )
  • namespace used in prefixing robot tf frame names and topic names .
~namespace_init_count (float, default: 1.0)
  • Starting index for robot names.
~delay_after_assignement (float, default: 0.5)
  • The unit is seconds. It defines the amount of delay after each robot assignment.
~global_frame (string, default: "/map")
  • frame name used as the global frame. In the single robot, it is the same as the "map_topic" parameter. In the multi-robot case, it is the frame name that corresponds to the global frame.

Tutorials

Tutorials on how to use the package are listed here.

Feedback

To report a bug, or suggest an enhancement, please create a Github issue here.

If you have a question, please post it on ROS answers, make sure your question is tagged by rrt_exploration so I get notified.

Acknowledgements & Citation

This package was written during my master's thesis at the American University of Sharjah. My thesis advisor is Dr. Shayok Mukhopadhyay.

This work has been published on IROS. If you are using this package, please cite our paper.

@INPROCEEDINGS{8202319,
author={H. Umari and S. Mukhopadhyay},
booktitle={2017 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
title={Autonomous robotic exploration based on multiple rapidly-exploring randomized trees},
year={2017},
volume={},
number={},
pages={1396-1402},
keywords={},
doi={10.1109/IROS.2017.8202319},
ISSN={},
month={Sept},}

Thesis title: "Multi-Robot Map Exploration Based on Multiple Rapidly-Exploring Randomized Trees"

Wiki: rrt_exploration (last edited 2023-11-25 07:52:55 by HassanUmari)