Only released in EOL distros:  

Package Summary

The explorer package utilizes frontier based exploration for multi-robot systems. Beside frontier detection, coordinated and uncoordinated exploration strategies are available to select goal points. Coordinated exploration enhances robot distribution and reduces redundancy in exploration reducing exploration time.

  • Maintainer status: developed
  • Maintainer: Daniel Neuhold <dneuhold AT edu.aau DOT at>
  • Author: Daniel Neuhold <dneuhold AT edu.aau DOT at>, Torsten Andre <torsten.andre AT aau DOT at>
  • License: BSD
  • Source: git https://github.com/aau-ros/aau_multi_robot.git (branch: hydro)

Package Summary

The explorer package utilizes frontier based exploration for multi-robot systems. Beside frontier detection, coordinated and uncoordinated exploration strategies are available to select goal points. Coordinated exploration enhances robot distribution and reduces redundancy in exploration reducing exploration time.

  • Maintainer status: developed
  • Maintainer: Daniel Neuhold <dneuhold AT edu.aau DOT at>
  • Author: Daniel Neuhold <dneuhold AT edu.aau DOT at>, Torsten Andre <torsten.andre AT aau DOT at>
  • License: BSD
  • Source: git https://github.com/aau-ros/aau_multi_robot.git (branch: indigo)

The explorer package utilizes frontier based exploration to discover environments autonomously operating a distributed multi-robot system. Beside frontier detection, coordinated and uncoordinated exploration strategies are available to select goal points. Coordinated exploration enhances robot distribution and reduces redundancy in exploration which result in improvement of efficiency in terms of exploration time.

Overview

The explorer package comprises multiple functionalities to perform frontier based exploration. Frontier detection is utilized on local and global costmaps to further select navigation goals in the environment to proceed with exploration. The assignment of robots to goals is accomplished according to coordinated and uncoordinated exploration strategies being applied for the distributed multi-robot system.

Auctioning thereby ensures negotiation among available goals to coordinate efficiently, distributing robots among the environment by minimizing the overall travel path. Additionally to frontier detection and selection, the explorer package is concerned with navigation to goal points by incorporating a simple action client utilizing move_base.

Exploration

Frontier based exploration is available for single and multi-robot systems. The exploration package is capable to operate in Simulation, e.g. Stage, but also to be deployed on a real robot system, e.g. Turtlebots and Pioneers. Additionally, coordinated robots comprise multiple frontiers as clusters to spatially interrelate groups of frontiers. Hence, multi-robot distribution is improved and number of participating goals, e.g. clusters, is narrowed. As a consequence, robots auction among clusters, implying less effort to negotiate a narrowed subset of elements.

Single Robot Exploration

As a single robot explores, communicational capabilities are irrelevant and exploration strategy is uncoordinated. Frontiers are therefore detected and selected according to "Nearest Frontier" strategy. The following video depicts single robot exploration utilizing Stage and "Nearest Frontier" strategy. Robots detect frontiers and represent them accordingly as red spheres in RVIZ, indicating selected frontiers as pink sphere.

Multi Robot Exploration

As a multi-robot exploration is assumed, robots maintaining a communication link to each other are capable to coordinate on cluster level. Thus, efficiency of exploration is increased as multiple robots distribute among the environment to explore different areas. Such a coordinated approach is depicted in the following video, utilizing two robots to decrease exploration time. Further, available clusters are represented by underlying frontiers with different colors. In the video, two robots explore an environment emulated by Stage, where one robot is depicted in RVIZ visualizing clusters, frontiers and selected goal points.

Please refer to the following paper to retrieve more information on the node:

@InProceedings{Andre2014,
  Title                    = {Coordinated Multi-Robot Exploration: Out of the Box Packages for {ROS}},
  Author                   = {Andre, T. and Neuhold, D. and Bettstetter, C.},
  Booktitle                = {Proc. of IEEE GLOBECOM WiUAV Workshop},
  Year                     = {2014},
  Month                    = dec,
}

You may obtain the paper from IEEEXplore or search in Google Scholar.

ROS API

Exploration Package

The explorer package publishes multiple topics to depict frontiers, clusters and goal points in RVIZ and to coordinate among multiple other robots participating in exploration. Further, required topics to be subscribed are listed.

Subscribed Topics

~<name>/map_merger/global_map (nav_msgs/OccupancyGrid)
  • Global map is utilized to detect frontiers at the entire environment. As multiple robots are operated, a global map is published by the map_merger node, incorporating explored areas from all robots.
~<name>/base_scan (sensor_msgs/LaserScan)
  • Data being send on this topic, are required to create a map and published by the laser scanner.
~<name>/frontiers (adhoc_communication/ExpFrontier)
  • Topic to exchange frontiers being detected by multiple robots.
~<name>/visited_frontiers (adhoc_communication/ExpFrontier)
  • Topic to exchange frontiers being previously selected by a robot as navigation goal.
~<name>/negotiation_list (adhoc_communication/ExpFrontier)
  • Negotiation list might be used to negotiate among frontiers in the environment to avoid multiple robots selecting an identical frontier.
~<name>/auction (adhoc_communication/ExpAuction)
  • Topic to auction frontiers. Auction messages are exchanged on this topic.
~<name>/all_positions (adhoc_communication/MmListOfPoints)
  • Topic used to exchange positions of all robots in the environment.

Published Topics

~<name>/visitedfrontierPoints (visualization_msgs/MarkerArray)
  • Visited frontier points are published on this topic to visualize them in RVIZ.
~<name>/goalPoint (geometry_msgs/PointStamped)
  • Goal points are published on this topic to visualize them in RVIZ.
~<name>/frontierPoints (visualization_msgs/MarkerArray)
  • Frontiers points are published on this topic to visualize them in RVIZ.
~<name>/cluster_grid_~ (nav_msgs/GridCells)
  • Topic to publish GridCells, indicating which cluster a frontier belongs.

Services

~<name>/adhoc_communication/send_frontier (adhoc_communication/SendExpFrontier)
  • Service to disseminate frontiers among all robots operating.
~<name>/adhoc_communication/send_auction (adhoc_communication/SendExpAuction)
  • Service to disseminate auctioning messages among all robots operating.

Parameters

~<name>/frontier_selection (int, default: 1)
  • Select exploration strategy. 0 indicates uncoordinated exploration, where 1 indicates coordinated exploration. As coordinated exploration is chosen, operating a single robot, communicational capabilities are unused and strategy is identical to uncoordinated exploration.
~<name>/local_costmap/width (int, default: 8)
  • Set the size of the local costmap to detect frontiers. The local costmap is centered at the robot and detects frontiers within its range.
~<name>/number_unreachable_for_cluster (int, default: 3)
  • Number of selected frontiers within a cluster, which are unreachable before neglecting the cluster as further navigation goal.

Wiki: explorer (last edited 2015-01-08 08:40:22 by AAU-Ros)