Classes | Functions
frontier_exploration Namespace Reference

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. More...
 
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. More...
 
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. More...
 
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. More...
 
template<typename T , typename S >
double pointsDistance (const T &one, const S &two)
 Calculate distance between two points. More...
 
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. More...
 
double polygonPerimeter (const geometry_msgs::Polygon &polygon)
 Calculate polygon perimeter. More...
 
template<typename T , typename S >
double yawOfVector (const T &origin, const S &end)
 Calculate the yaw of vector defined by origin and end points. More...
 

Function Documentation

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.

Parameters
resultIndex of located cell
startIndex initial cell to search from
valSpecified value to search for
costmapReference to map data
Returns
True if a cell with the requested value was found

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.

Parameters
idxinput cell index
costmapReference to map data
Returns
neighbour cell indexes

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.

Parameters
idxinput cell index
costmapReference to map data
Returns
neighbour cell indexes

Definition at line 51 of file costmap_tools.h.

template<typename T >
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.

Parameters
pointPoint to test
polygonPolygon to test
Returns
True if point is inside polygon, false otherwise

Definition at line 58 of file geometry_tools.h.

template<typename T , typename S >
double frontier_exploration::pointsDistance ( const T &  one,
const S &  two 
)

Calculate distance between two points.

Parameters
onePoint one
twoPoint two
Returns
Distance between two points

Definition at line 17 of file geometry_tools.h.

template<typename T , typename S >
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.

Parameters
onePoint one
twoPoint two
proximityProximity distance
Returns
True if approximately adjacent, false otherwise

Definition at line 47 of file geometry_tools.h.

double frontier_exploration::polygonPerimeter ( const geometry_msgs::Polygon &  polygon)

Calculate polygon perimeter.

Parameters
polygonPolygon to process
Returns
Perimeter of polygon

Definition at line 26 of file geometry_tools.h.

template<typename T , typename S >
double frontier_exploration::yawOfVector ( const T &  origin,
const S &  end 
)

Calculate the yaw of vector defined by origin and end points.

Parameters
originOrigin point
endEnd point
Returns
Yaw angle of vector

Definition at line 76 of file geometry_tools.h.



frontier_exploration
Author(s): Paul Bovbel
autogenerated on Mon Jun 10 2019 13:25:00