A class that will identify frontiers in a partially explored map. More...
#include <explore_frontier.h>
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< Frontier > | frontiers_ |
Private Attributes | |
float | costmapResolution_ |
uint | lastMarkerCount_ |
nav_msgs::OccupancyGrid | map_ |
navfn::NavfnROS * | planner_ |
A class that will identify frontiers in a partially explored map.
Definition at line 79 of file explore_frontier.h.
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.
virtual void explore::ExploreFrontier::findFrontiers | ( | costmap_2d::Costmap2DROS & | costmap_ | ) | [protected, virtual] |
Finds frontiers and populates frontiers_.
costmap | The costmap to search for frontiers |
virtual 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.
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 |
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.
float explore::ExploreFrontier::getFrontierCost | ( | const Frontier & | frontier | ) | [protected, virtual] |
Calculates cost to explore frontier.
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.
frontier | to evaluate |
Definition at line 97 of file explore_frontier.cpp.
virtual bool explore::ExploreFrontier::getFrontiers | ( | costmap_2d::Costmap2DROS & | costmap, | |
std::vector< geometry_msgs::Pose > & | frontiers | |||
) | [virtual] |
Returns all frontiers.
costmap | The costmap to search for frontiers | |
frontiers | Will be filled with current frontiers |
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.
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.
markers | All markers will be added to this vector |
float explore::ExploreFrontier::costmapResolution_ [private] |
Definition at line 84 of file explore_frontier.h.
std::vector<Frontier> explore::ExploreFrontier::frontiers_ [protected] |
Definition at line 88 of file explore_frontier.h.
uint explore::ExploreFrontier::lastMarkerCount_ [private] |
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.