$search

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, tf::Stamped< tf::Pose > robot_pose, 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)
 Calculates how much the robot would have to turn to face this frontier.

Protected Attributes

std::vector< Frontierfrontiers_

Private Attributes

float costmapResolution_
uint lastMarkerCount_
nav_msgs::OccupancyGrid map_
navfn::NavfnROSplanner_

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

explore::ExploreFrontier::ExploreFrontier (  ) 

Definition at line 50 of file explore_frontier.cpp.

explore::ExploreFrontier::~ExploreFrontier (  )  [virtual]

Definition at line 58 of file explore_frontier.cpp.


Member Function Documentation

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

Finds frontiers and populates frontiers_.

Parameters:
costmap The costmap to search for frontiers

Definition at line 163 of file explore_frontier.cpp.

bool explore::ExploreFrontier::getExplorationGoals ( costmap_2d::Costmap2DROS costmap,
tf::Stamped< tf::Pose robot_pose,
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:
costmap The costmap to search for frontiers
start The current position of the robot
goals Will be filled with sorted list of current goals
planner A planner to evaluate the cost of going to any frontier
potential_scale A scaling for the potential to a frontier goal point for the frontier's cost
orientation_scale A scaling for the change in orientation required to get to a goal point for the frontier's cost
gain_scale A 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 101 of file explore_frontier.cpp.

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

Calculates cost to explore frontier.

Parameters:
frontier to evaluate

Definition at line 78 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:
frontier to evaluate

Definition at line 97 of file explore_frontier.cpp.

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

Returns all frontiers.

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

Definition at line 63 of file explore_frontier.cpp.

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

Calculates how much the robot would have to turn to face this frontier.

Parameters:
frontier to evaluate
robot_pose current pose

Definition at line 88 of file explore_frontier.cpp.

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

Returns markers representing all frontiers.

Parameters:
markers All markers will be added to this vector

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.

Definition at line 81 of file explore_frontier.h.

Definition at line 86 of file explore_frontier.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


explore
Author(s): Charles DuHadway (maintained by Benjamin Pitzer)
autogenerated on Mon Mar 4 11:32:51 2013