Classes | |
class | BoundedExploreLayer |
costmap_2d layer plugin that holds the state for a bounded frontier exploration task. Manages the boundary polygon, superimposes the polygon on the overall exploration costmap, and processes costmap to find next frontier to explore. More... | |
class | FrontierExplorationClient |
Client for FrontierExplorationServer that receives control points from rviz, and creates boundary polygon for frontier exploration. More... | |
class | FrontierExplorationServer |
Server for frontier exploration action, runs the state machine associated with a structured frontier exploration task and manages robot movement through move_base. More... | |
class | FrontierSearch |
Thread-safe implementation of a frontier-search task for an input costmap. More... | |
Functions | |
bool | nearestCell (unsigned int &result, unsigned int start, unsigned char val, const costmap_2d::Costmap2D &costmap) |
Find nearest cell of a specified value. | |
std::vector< unsigned int > | nhood4 (unsigned int idx, const costmap_2d::Costmap2D &costmap) |
Determine 4-connected neighbourhood of an input cell, checking for map edges. | |
std::vector< unsigned int > | nhood8 (unsigned int idx, const costmap_2d::Costmap2D &costmap) |
Determine 8-connected neighbourhood of an input cell, checking for map edges. | |
template<typename T > | |
bool | pointInPolygon (const T &point, const geometry_msgs::Polygon &polygon) |
Evaluate if point is inside area defined by polygon. Undefined behaviour for points on line. | |
template<typename T , typename S > | |
double | pointsDistance (const T &one, const S &two) |
Calculate distance between two points. | |
template<typename T , typename S > | |
bool | pointsNearby (const T &one, const S &two, const double &proximity) |
Evaluate whether two points are approximately adjacent, within a specified proximity distance. | |
double | polygonPerimeter (const geometry_msgs::Polygon &polygon) |
Calculate polygon perimeter. | |
template<typename T , typename S > | |
double | yawOfVector (const T &origin, const S &end) |
Calculate the yaw of vector defined by origin and end points. |
bool frontier_exploration::nearestCell | ( | unsigned int & | result, |
unsigned int | start, | ||
unsigned char | val, | ||
const costmap_2d::Costmap2D & | costmap | ||
) |
Find nearest cell of a specified value.
result | Index of located cell |
start | Index initial cell to search from |
val | Specified value to search for |
costmap | Reference to map data |
Definition at line 86 of file costmap_tools.h.
std::vector<unsigned int> frontier_exploration::nhood4 | ( | unsigned int | idx, |
const costmap_2d::Costmap2D & | costmap | ||
) |
Determine 4-connected neighbourhood of an input cell, checking for map edges.
idx | input cell index |
costmap | Reference to map data |
Definition at line 18 of file costmap_tools.h.
std::vector<unsigned int> frontier_exploration::nhood8 | ( | unsigned int | idx, |
const costmap_2d::Costmap2D & | costmap | ||
) |
Determine 8-connected neighbourhood of an input cell, checking for map edges.
idx | input cell index |
costmap | Reference to map data |
Definition at line 51 of file costmap_tools.h.
bool frontier_exploration::pointInPolygon | ( | const T & | point, |
const geometry_msgs::Polygon & | polygon | ||
) |
Evaluate if point is inside area defined by polygon. Undefined behaviour for points on line.
point | Point to test |
polygon | Polygon to test |
Definition at line 58 of file geometry_tools.h.
double frontier_exploration::pointsDistance | ( | const T & | one, |
const S & | two | ||
) |
Calculate distance between two points.
one | Point one |
two | Point two |
Definition at line 17 of file geometry_tools.h.
bool frontier_exploration::pointsNearby | ( | const T & | one, |
const S & | two, | ||
const double & | proximity | ||
) |
Evaluate whether two points are approximately adjacent, within a specified proximity distance.
one | Point one |
two | Point two |
proximity | Proximity distance |
Definition at line 47 of file geometry_tools.h.
double frontier_exploration::polygonPerimeter | ( | const geometry_msgs::Polygon & | polygon | ) |
Calculate polygon perimeter.
polygon | Polygon to process |
Definition at line 26 of file geometry_tools.h.
double frontier_exploration::yawOfVector | ( | const T & | origin, |
const S & | end | ||
) |
Calculate the yaw of vector defined by origin and end points.
origin | Origin point |
end | End point |
Definition at line 76 of file geometry_tools.h.