Public Member Functions | Private Member Functions | 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 (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< Frontierfrontiers_
size_t last_markers_count_
nav_msgs::OccupancyGrid map_
navfn::NavfnROS *const planner_

Detailed Description

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

Definition at line 88 of file explore_frontier.h.


Constructor & Destructor Documentation

Constructs ExploreFrintier with costmap to work on.

Parameters:
costmapThe costmap to search for frontiers
plannerA planner to evaluate the cost of going to any frontier
Exceptions:
std::invalid_argumentif any argument is NULL

Definition at line 46 of file explore_frontier.cpp.


Member Function Documentation

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.

Parameters:
startThe current position of the robot
goalsWill be filled with sorted list of current goals
cost_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 96 of file explore_frontier.cpp.

double explore::ExploreFrontier::getFrontierCost ( const Frontier frontier) [private]

Calculates cost to explore frontier.

Parameters:
frontierto 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.

Parameters:
frontierto evaluate

Definition at line 92 of file explore_frontier.cpp.

bool explore::ExploreFrontier::getFrontiers ( std::vector< geometry_msgs::Pose > &  frontiers)

Returns all frontiers.

Parameters:
frontiersWill be filled with current frontiers
Returns:
True if at least one frontier was found

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.

Parameters:
frontierto evaluate
robot_posecurrent pose

Definition at line 80 of file explore_frontier.cpp.

void explore::ExploreFrontier::getVisualizationMarkers ( visualization_msgs::MarkerArray &  markers)

Returns markers representing all frontiers.

Parameters:
markersAll markers will be added to this vector

Definition at line 322 of file explore_frontier.cpp.


Member Data Documentation

Definition at line 92 of file explore_frontier.h.

Definition at line 91 of file explore_frontier.h.

Definition at line 96 of file explore_frontier.h.

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.

Definition at line 93 of file explore_frontier.h.


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


explore
Author(s): Jiri Horner
autogenerated on Sun Mar 26 2017 03:48:06