This repository contains the ROS package that implements the works from the algorithm "CQLite: Coverage-biased Q-Learning Lite for Efficient Multi-Robot Exploration" for mobile robots. It uses the occupancy grid as a map representation.
The following figure shows the view of CQLite exploration:
If you use this work, please cite our paper: Latif E, Parasuraman R. Communication-efficient multi-robot exploration using coverage-biased distributed q-learning. IEEE Robotics and Automation Letters. 2024 Jan 24.
IEEE Published version: https://ieeexplore.ieee.org/abstract/document/10413563 Preprint available at https://arxiv.org/abs/2307.00500
The packgae has 5 different ROS nodes:
-
Global frontier point detector node.
-
Local frontier point detector node.
-
CQLite filter node.
-
CQLite planner node.
-
opencv-based frontier detector node.
The package has been tested on both ROS Noetic and ROS Melodic for both simulated and hardware Turtlebot3 robot (burger). The following requirements are needed before installing the package:
1- You should have installed a ROS distribution (indigo or later. Recommended is either noetic or melodic).
2- Created a workspace.
3- Install the "gmapping" ROS package: on PC and each robot, as:
$ sudo apt-get install ros-noetic-gmapping
4- Install the ROS navigation stack. You can do that with the following command (assuming Ubuntu, ROS Kinetic):
$ sudo apt-get install ros-noetic-navigation
5- You should have Python 3.6+
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
Download the package and place it inside the /src
folder of your ROS workspace. And then compile using catkin_make
.
This package provides an exploration strategy for cooperative robot. However, for it to work, you should have set your robots ready using the navigation stack. Additionally, the robots must be set and prepared as follows.
For the cooperative robotic 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.
All robot's frames should be prefixed by its name. Naming of robots starts from "/tb3_0", "/tb3_1", ... and so on.
All the nodes and topics running on a robot must also be prefixed by its name. For tb3_0, node names should look like: /tb3_0/slam_gmapping
.
And topic names should be like: /tb3_0/odom
, /tb3_0/map
, /tb3_0/scan
, ..etc.
Each robot should have a local map generated from the gmapping package.
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.
There are 4 types of nodes; nodes for detecting frontier points in an occupancy grid map, a node for filtering the detected points, a node for assigning the points to the robots, and a node for planning path for robot. The following figure shows the system arcitecture of CQLite:
The global_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.
~map_topic
(string, default: "/tb3_0/map"): This parameter defines the topic name on which the node will recieve the map.
-
The map (Topic name is defined by the
~map_topic
parameter) (nav_msgs/OccupancyGrid) -
clicked_point
(geometry_msgs/PointStamped Message): Theglobal_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 CQLite will start detecting frontier points. The five points are intended to be published from Rviz using button.
-
detected_points
(geometry_msgs/PointStamped Message): The topic on which the node publishes detected frontier points. -
~shapes
(visualization_msgs/Marker Message): On this topic, the node publishes line shapes to visualize the CQLite using Rviz.
This node is similar to the global_frontier_detector. However, it works differently, as a connected graph here keeps resetting every time a frontier point is detected. This node is intended to be run along side the global__frontier_detector node, it is responsible for fast detection of frontier points that lie in the close vicinity of the robot.
All detectors will be publishing detected frontier points on the same topic (/detected_points
).
-
~robot_frame
(string, default: "/tb3_0/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: "/tb3_0/map"): This parameter defines the topic name on which the node will recieve the map.
-
The map (Topic name is defined by the
~map_topic
parameter) (nav_msgs/OccupancyGrid). -
clicked_point
(geometry_msgs/PointStamped Message): Thelobal_frontier_detector
also subscribes to this topic similar to the global_frontier_detector.
- Same as global frontier detector with local prefix
This node is another frontier detector, but it is not based on CQLite. This node uses OpenCV tools to detect frontier points. It is intended to be run alone, and only one instance should be run.
Originally this node was implemented for comparison against the standard frontier detectors. Running this node along side the CQLite detectors (local and global) may enhance the speed of frontier points detection.
~map_topic
(string, default: "/tb3_0/map"): This parameter defines the topic name on which the node will recieve the map.
- The map (Topic name is defined by the
~map_topic
parameter) (nav_msgs/OccupancyGrid)
-
detected_points
(geometry_msgs/PointStamped Message): The topic on which the node publishes the detected frontier points. -
shapes
(visualization_msgs/Marker Message): On this topic, the node publishes the detected points to be visualized using Rviz.
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. Filteration includes the delection of old and invalid points, and it also dicards redundant points.
~map_topic
(string, default: "/tb3_0/map"): This parameter defines the topic name on which the node will recieve the map. The map is used to know which points are no longer frontier points (old points).~costmap_clearing_threshold
(float, default: 70.0): Any frontier point that has an occupancy value greater than this threshold will be considered invalid. The occupancy value is obtained from the costmap.~info_radius
(float, default: 1.0): The information radius used in calculating the information gain of frontier points.~goals_topic
(string, default: "/detected_points"): defines the topic on which the node receives detcted frontier points.~rate
(float, default: 100): node loop rate (in Hz).
-
The map (Topic name is defined by the
~map_topic
parameter) (nav_msgs/OccupancyGrid). -
tb3_0/move_base/global_costmap/costmap
(nav_msgs/OccupancyGrid): where x (in robot_x) refers to robot's number.
The filter node subscribes for all the costmap topics of all the robots, the costmap is required therefore. Normally, costmaps should be published by the navigation stack (after bringing up the navigation stack on the robots, each robot will have a costmap).
- The goals topic (Topic name is defined by the
~goals_topic
parameter)(geometry_msgs/PointStamped Message): The topic on which the filter node receives detected frontier points.
-
frontiers
(visualization_msgs/Marker Message): The topic on which the filter node publishes the received frontier points for visualiztion on Rviz. -
centroids
(visualization_msgs/Marker Message): The topic on which the filter node publishes only the filtered frontier points for visualiztion on Rviz. -
filtered_points
(PointArray): All the filtered points are sent as an array of points to the assigner node on this topic.
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
. This is why you have bring up the navigation stack on your robots.
-
~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 meters. 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 meters. This parameter defines the hysteresis radius. -
~hysteresis_gain
(float, default: 2.0): The unit is metesr. This parameter defines the hysteresis gain. -
~frontiers_topic
(string, default: "/filtered_points"): The topic on which the assigner node receives filtered frontier points. -
~delay_after_assignement
(float, default: 0.5): The unit is seconds. It defines the amount of delay after each robot assignment. -
~rate
(float, default: 100): node loop rate (in Hz).
-
The map (Topic name is defined by the
~map_topic
parameter) (nav_msgs/OccupancyGrid). -
Filtered frontier points topic (Topic name is defined by the
~frontiers_topic
parameter) (PointArray).
The assigner node does not publish anything. It sends the assigned point to the move_base
using Actionlib.
Run the CQLite package after installation on a robot and source bash and /devel/setup.bash file:
$ roslaunch cqlite cqlite_exploration.launch
-
Ehsan Latif - PhD Candidate
-
Dr. Ramviyas Parasuraman - Lab Director
Heterogeneous Robotics Lab (HeRoLab), School of Computing, University of Georgia.
For further information, contact Dr. Ramviyas Parasuraman [email protected]