A class that will identify frontiers in a partially explored map. More...
#include <explore_frontier.h>
Public Member Functions | |
ExploreFrontier (Costmap2DClient *costmap, navfn::NavfnROS *planner) | |
Constructs ExploreFrintier with costmap to work on. | |
bool | getExplorationGoals (tf::Stamped< tf::Pose > start, 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. | |
bool | getFrontiers (std::vector< geometry_msgs::Pose > &frontiers) |
Returns all frontiers. | |
void | getVisualizationMarkers (visualization_msgs::MarkerArray &markers) |
Returns markers representing all frontiers. | |
Private Member Functions | |
void | findFrontiers () |
Finds frontiers and populates frontiers_. | |
double | getFrontierCost (const Frontier &frontier) |
Calculates cost to explore frontier. | |
double | getFrontierGain (const Frontier &frontier) const |
Calculates potential information gain of exploring frontier. | |
double | getOrientationChange (const Frontier &frontier, const tf::Stamped< tf::Pose > &robot_pose) const |
Calculates how much the robot would have to turn to face this frontier. | |
Private Attributes | |
costmap_2d::Costmap2D *const | costmap_ |
Costmap2DClient *const | costmap_client_ |
std::vector< Frontier > | frontiers_ |
size_t | last_markers_count_ |
nav_msgs::OccupancyGrid | map_ |
navfn::NavfnROS *const | planner_ |
A class that will identify frontiers in a partially explored map.
Definition at line 88 of file explore_frontier.h.
explore::ExploreFrontier::ExploreFrontier | ( | Costmap2DClient * | costmap, |
navfn::NavfnROS * | planner | ||
) |
Constructs ExploreFrintier with costmap to work on.
costmap | The costmap to search for frontiers |
planner | A planner to evaluate the cost of going to any frontier |
std::invalid_argument | if any argument is NULL |
Definition at line 46 of file explore_frontier.cpp.
void explore::ExploreFrontier::findFrontiers | ( | ) | [private] |
Finds frontiers and populates frontiers_.
Definition at line 165 of file explore_frontier.cpp.
bool explore::ExploreFrontier::getExplorationGoals | ( | tf::Stamped< tf::Pose > | start, |
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.
start | The current position of the robot |
goals | Will be filled with sorted list of current goals |
cost_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.
Definition at line 96 of file explore_frontier.cpp.
double explore::ExploreFrontier::getFrontierCost | ( | const Frontier & | frontier | ) | [private] |
Calculates cost to explore frontier.
frontier | to evaluate |
Definition at line 71 of file explore_frontier.cpp.
double explore::ExploreFrontier::getFrontierGain | ( | const Frontier & | frontier | ) | const [private] |
Calculates potential information gain of exploring frontier.
frontier | to evaluate |
Definition at line 92 of file explore_frontier.cpp.
bool explore::ExploreFrontier::getFrontiers | ( | std::vector< geometry_msgs::Pose > & | frontiers | ) |
Returns all frontiers.
frontiers | Will be filled with current frontiers |
Definition at line 57 of file explore_frontier.cpp.
double explore::ExploreFrontier::getOrientationChange | ( | const Frontier & | frontier, |
const tf::Stamped< tf::Pose > & | robot_pose | ||
) | const [private] |
Calculates how much the robot would have to turn to face this frontier.
frontier | to evaluate |
robot_pose | current pose |
Definition at line 80 of file explore_frontier.cpp.
void explore::ExploreFrontier::getVisualizationMarkers | ( | visualization_msgs::MarkerArray & | markers | ) |
Returns markers representing all frontiers.
markers | All markers will be added to this vector |
Definition at line 322 of file explore_frontier.cpp.
costmap_2d::Costmap2D* const explore::ExploreFrontier::costmap_ [private] |
Definition at line 92 of file explore_frontier.h.
Costmap2DClient* const explore::ExploreFrontier::costmap_client_ [private] |
Definition at line 91 of file explore_frontier.h.
std::vector<Frontier> explore::ExploreFrontier::frontiers_ [private] |
Definition at line 96 of file explore_frontier.h.
size_t explore::ExploreFrontier::last_markers_count_ [private] |
Definition at line 98 of file explore_frontier.h.
nav_msgs::OccupancyGrid explore::ExploreFrontier::map_ [private] |
Definition at line 95 of file explore_frontier.h.
navfn::NavfnROS* const explore::ExploreFrontier::planner_ [private] |
Definition at line 93 of file explore_frontier.h.