Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes
explore::ExploreFrontier Class Reference

A class that will identify frontiers in a partially explored map. More...

#include <explore_frontier.h>

List of all members.

Public Member Functions

 ExploreFrontier ()
virtual bool getExplorationGoals (costmap_2d::Costmap2DROS &costmap, geometry_msgs::Point start, navfn::NavfnROS *planner, std::vector< geometry_msgs::Pose > &goals, double cost_scale, double orientation_scale, double gain_scale)
 Returns a list of frontiers, sorted by the planners estimated cost to visit each frontier.
virtual bool getFrontiers (costmap_2d::Costmap2DROS &costmap, std::vector< geometry_msgs::Pose > &frontiers)
 Returns all frontiers.
virtual void getVisualizationMarkers (std::vector< visualization_msgs::Marker > &markers)
 Returns markers representing all frontiers.
virtual ~ExploreFrontier ()

Protected Member Functions

virtual void findFrontiers (costmap_2d::Costmap2DROS &costmap_)
 Finds frontiers and populates frontiers_.
virtual float getFrontierCost (const Frontier &frontier)
 Calculates cost to explore frontier.
virtual float getFrontierGain (const Frontier &frontier, double map_resolution)
 Calculates potential information gain of exploring frontier.
virtual double getOrientationChange (const Frontier &frontier, const tf::Stamped< tf::Pose > &robot_pose)

Protected Attributes

std::vector< Frontierfrontiers_

Private Attributes

float costmapResolution_
uint lastMarkerCount_
nav_msgs::OccupancyGrid map_
navfn::NavfnROS * planner_

Detailed Description

A class that will identify frontiers in a partially explored map.

Definition at line 79 of file explore_frontier.h.


Constructor & Destructor Documentation

Definition at line 53 of file explore_frontier.cpp.

Definition at line 61 of file explore_frontier.cpp.


Member Function Documentation

void explore::ExploreFrontier::findFrontiers ( costmap_2d::Costmap2DROS &  costmap_) [protected, virtual]

Finds frontiers and populates frontiers_.

Parameters:
costmapThe costmap to search for frontiers

Definition at line 191 of file explore_frontier.cpp.

bool explore::ExploreFrontier::getExplorationGoals ( costmap_2d::Costmap2DROS &  costmap,
geometry_msgs::Point  start,
navfn::NavfnROS *  planner,
std::vector< geometry_msgs::Pose > &  goals,
double  cost_scale,
double  orientation_scale,
double  gain_scale 
) [virtual]

Returns a list of frontiers, sorted by the planners estimated cost to visit each frontier.

Parameters:
costmapThe costmap to search for frontiers
startThe current position of the robot
goalsWill be filled with sorted list of current goals
plannerA planner to evaluate the cost of going to any frontier
potential_scaleA scaling for the potential to a frontier goal point for the frontier's cost
orientation_scaleA scaling for the change in orientation required to get to a goal point for the frontier's cost
gain_scaleA scaling for the expected information gain to get to a goal point for the frontier's cost
Returns:
True if at least one frontier was found

The frontiers are weighted by a simple cost function, which prefers frontiers which are large and close: frontier cost = travel cost / frontier size

Several different positions are evaluated for each frontier. This improves the robustness of goals which may lie near other obstacles which would prevent planning.

Definition at line 104 of file explore_frontier.cpp.

float explore::ExploreFrontier::getFrontierCost ( const Frontier frontier) [protected, virtual]

Calculates cost to explore frontier.

Parameters:
frontierto evaluate

Definition at line 81 of file explore_frontier.cpp.

float explore::ExploreFrontier::getFrontierGain ( const Frontier frontier,
double  map_resolution 
) [protected, virtual]

Calculates potential information gain of exploring frontier.

Parameters:
frontierto evaluate

Definition at line 100 of file explore_frontier.cpp.

bool explore::ExploreFrontier::getFrontiers ( costmap_2d::Costmap2DROS &  costmap,
std::vector< geometry_msgs::Pose > &  frontiers 
) [virtual]

Returns all frontiers.

Parameters:
costmapThe costmap to search for frontiers
frontiersWill be filled with current frontiers
Returns:
True if at least one frontier was found

Definition at line 66 of file explore_frontier.cpp.

double explore::ExploreFrontier::getOrientationChange ( const Frontier frontier,
const tf::Stamped< tf::Pose > &  robot_pose 
) [protected, virtual]

Definition at line 91 of file explore_frontier.cpp.

void explore::ExploreFrontier::getVisualizationMarkers ( std::vector< visualization_msgs::Marker > &  markers) [virtual]

Returns markers representing all frontiers.

Parameters:
markersAll markers will be added to this vector

Definition at line 383 of file explore_frontier.cpp.


Member Data Documentation

Definition at line 84 of file explore_frontier.h.

Definition at line 88 of file explore_frontier.h.

Definition at line 83 of file explore_frontier.h.

nav_msgs::OccupancyGrid explore::ExploreFrontier::map_ [private]

Definition at line 81 of file explore_frontier.h.

navfn::NavfnROS* explore::ExploreFrontier::planner_ [private]

Definition at line 86 of file explore_frontier.h.


The documentation for this class was generated from the following files:


explore_hrl
Author(s): Travis Deyle
autogenerated on Wed Nov 27 2013 11:48:01