Only released in EOL distros:  

Package Summary

Frontier exploration implementation in ROS, accepts exploration goals via actionlib (Rviz UI provided), sends movement commands to move_base.

Package Summary

Implementation of frontier exploration for ROS, extending on the existing navigation stack (costmap_2d, move_base). It accepts exploration goals via actionlib (Rviz UI provided), sends movement commands to move_base.

Package Summary

Implementation of frontier exploration for ROS, extending on the existing navigation stack (costmap_2d, move_base). It accepts exploration goals via actionlib (Rviz UI provided), sends movement commands to move_base.

Package Summary

Implementation of frontier exploration for ROS, extending on the existing navigation stack (costmap_2d, move_base). It accepts exploration goals via actionlib (Rviz UI provided), sends movement commands to move_base.

Please check the FAQ for common problems, or open an issue if still unsolved.

Overview

The best way to try frontier_exploration is using the demo provided in husky_navigation, see the demo tutorial.

Functionality

The frontier_exploration package provides a costmap_2d layer plugin BoundedExploreLayer, and actionlib client/server nodes explore_client and explore_server.

The provided nodes can be used to demo the functionality of the costmap layer by executing a frontier exploration task bounded by a user-defined polygon area. Layer BoundedExploreLayer can certainly be used for more complex exploration tasks, functionality is exposed through two Services: UpdatePolygonBoundary and GetNextFrontier.

To run this demo on your host, see frontier_exploration#For_running_a_demo section.

Also, this video is an example of frontier_exploration integrated with Turtlebot (turtlebot_samples package is used).

Requirements

Frontier exploration using this package requires a real or simulated robot configuration that provides the following functionality:

  1. Laser scanner or similar sensor that can clear space and mark obstacles.
  2. Properly configured navigation stack that can accept action goals to move_base.

  3. (Optional) Global /map provided by map_server, gmapping, or the global costmap from move_base

Usage

For running a demo

Using a pre-existing robot and config, you can run a demo and see how this package works.

  1. Install dependency.
    sudo apt-get install ros-$ROS_DISTRO-frontier-exploration ros-$ROS_DISTRO-navigation-stage
  2. Run the necessary nodes one-by-one from separate terminal:
    roslaunch navigation_stage move_base_gmapping_5cm.launch
    
    roslaunch navigation_stage move_base.xml
    
    roslaunch frontier_exploration global_map.launch
    RViz pops up, then a demo robot appears around the center in a map.
  3. Open a Marker plugin on RViz (RViz plugins can be chosen in a popup window that you can open by "Add" button).

  4. Pull down "Displays --> Marker --> Marker Topic" menu then select "exploration_polygon_marker" topic.

  5. On the map on RViz, think of a region that you like the robot to explore.
  6. Click "Publish Point" at the top of RViz.

  7. Click **a single corner** of n corners of the region (n=4 if your region is square/rectangular, to be pedantic).

  8. Repeat step 6 and 7 above for n times. After that you'll see a polygon with n corners.
  9. Do the step 6 once again, then this time click anywhere within the polygon.

At this point the demo robot should start moving as the video above.

For developers

If you just want to start taking advantage of the functionality of this package, this tutorial in husky_navigation package helps.

If you like to understand a little more in depth, generally, when launched explore_server will spin until it receives an exploration goal. To submit a goal:

  1. Use explore_client and RViz - create a marker display in Rviz for the exploration_polygon_marker topic, and use the "Click Point" tool from the toolbar to mark the exploration boundary. Watch the ROS console for feedback regarding your selected boundary.

  2. Submit a goal to the server with your own node via an actionlib SimpleActionClient.

The exploration goal contains an initial point to start exploration, and a polygonal boundary to limit the exploration scope. To run an unbounded exploration task, simply leave the boundary blank.

Once the server receives a goal, it will create the initial exploration map, start processing sensor/costmap data, and issuing move_base action goals. By default, the exploration task will explore all areas within boundary (whether previously visited or not). Sample launch files for several use cases are provided below.

Exploration without /map data

When running the action server/client without a global /map information source, enable the resize_to_boundary parameter to dynamically resize the map based on the action goal's polygon boundary. Error messages thrown up by costmap_2d regarding the sensor being outside of map bounds will occur when the robot is traveling outside the exploration boundary. These can be safely ignored, and could be suppressed using rosconsole configuration files.

If not using resize_to_boundary (e.g. running unbounded exploration), make sure the costmap is configured with a large enough height/width.

Sample launch file: no_global_map.launch

Exploration with /map data

When running the action server/client with a global /map information source (either from map_server or gmapping), the exploration costmap will match size/resolution to the external map source map loaded by the static layer, so it is important to disable the resize_to_boundary parameter and that the global_frame of the exploration costmap matches that of the external /map.

When exploring with gmapping, you must also disable explore_clear_space to prevent the node from re-exploring known areas.

Sample launch file: global_map.launch

Provided Components

explore_client

The explore_client node listens to points published by Rviz and builds an ExploreTask action goal to send to explore_server.

Actions Called

explore_server (frontier_exploration/ExploreTask)
  • Client for exploration goals to explore_server.

Subscribed Topics

/clicked_point (geometry_msgs/PointStamped)
  • Clicked points from rviz tool.

Published Topics

exploration_polygon_marker (visualization_msgs/Marker)
  • Boundary visualization via clicked points.

explore_server

The explore_server node executes exploration actions for any connected clients. It uses a costmap_2d object to keep track of the exploration progress, and creates movement goals for move_base as necessary.

Actions Provided

explore_server (frontier_exploration/ExploreTask)

  • Server for incoming exploration task requests

Actions Called

move_base (move_base_msgs/MoveBaseAction)
  • Client for movement goals to move_base.

Services Called

~explore_costmap/explore_boundary/update_boundary_polygon (frontier_exploration/UpdateBoundaryPolygon)
  • (Internal Service from Costmap) Set boundary for exploration task.
~explore_costmap/explore_boundary/get_next_frontier (frontier_exploration/GetNextFrontier)
  • (Internal Service from Costmap) Get the pose of the next frontier to explore.

Parameters

~explore_costmap (plugins)
  • Configuration for internal costmap layers, expected to include BoundedExploreLayer.
~frequency (float, default: 0.0)
  • Frequency with which to reprocess the costmap for next frontier goal. If 0.0, only ask for new frontier when last frontier was reached via move_base. Higher frequencies submit move_base goals more often and create 'smoother' exploration.
~goal_aliasing (float, default: 0.1)
  • When frequency > 0.0, ~goal_aliasing is the required distance delta between the last goal and a new goal, before the new goal is submitted to move_base. It is safe to set to anywhere within sensor_range/2 > ~goal_aliasing > 0.0, and this parameter will reduce the amount of redundant goals sent during 'smooth' exploration.

BoundedExploreLayer

The frontier_exploration::BoundedExploreLayer layer is a costmap_2d plugin that implements several functions required to execute a frontier exploration task.

Published Topics

~frontiers (sensor_msgs/PointCloud2)
  • Pointcloud pcl::Pointcloud<pcl::PointXYZI> marking all frontiers detected when service ~get_next_frontier is called, with the selected frontier marked using a higher intensity point.

Services

~update_boundary_polygon (frontier_exploration/UpdateBoundaryPolygon)
  • Set boundary for exploration task.
~get_next_frontier (frontier_exploration/GetNextFrontier)
  • Get the pose of the next frontier to explore.

Parameters

~resize_to_boundary (bool, default: false)
  • When receiving a polygonal boundary via ~update_boundary_polygon, resize the layer's parent costmap to the boundary extrema.
~frontier_travel_point (string, default: closest)
  • When outputting pose of next frontier via ~get_next_frontier, define the geometric property of frontier to output as pose.position. Available: closest point to robot, middle point of frontier, centroid (cartesian average) of all frontier points.
~explore_clear_space (bool, default: true)
  • Configure whether the exploration task should explore all clear space (true), or just unknown space (false).

Wiki: frontier_exploration (last edited 2017-03-08 03:02:10 by MikePurvis)