Public Member Functions | Protected Member Functions | Private Attributes
frontier_exploration::FrontierSearch Class Reference

Thread-safe implementation of a frontier-search task for an input costmap. More...

#include <frontier_search.h>

List of all members.

Public Member Functions

 FrontierSearch (costmap_2d::Costmap2D &costmap)
 Constructor for search task.
std::list< Frontier > searchFrom (geometry_msgs::Point position)
 Runs search implementation, outward from the start position.

Protected Member Functions

Frontier buildNewFrontier (unsigned int initial_cell, unsigned int reference, std::vector< bool > &frontier_flag)
 Starting from an initial cell, build a frontier from valid adjacent cells.
bool isNewFrontierCell (unsigned int idx, const std::vector< bool > &frontier_flag)
 isNewFrontierCell Evaluate if candidate cell is a valid candidate for a new frontier.

Private Attributes

costmap_2d::Costmap2Dcostmap_
unsigned char * map_
unsigned int size_x_
unsigned int size_y_

Detailed Description

Thread-safe implementation of a frontier-search task for an input costmap.

Definition at line 12 of file frontier_search.h.


Constructor & Destructor Documentation

Constructor for search task.

Parameters:
costmapReference to costmap data to search.

Definition at line 17 of file frontier_search.cpp.


Member Function Documentation

Frontier frontier_exploration::FrontierSearch::buildNewFrontier ( unsigned int  initial_cell,
unsigned int  reference,
std::vector< bool > &  frontier_flag 
) [protected]

Starting from an initial cell, build a frontier from valid adjacent cells.

Parameters:
initial_cellIndex of cell to start frontier building
referenceReference index to calculate position from
frontier_flagFlag vector indicating which cells are already marked as frontiers
Returns:

Definition at line 79 of file frontier_search.cpp.

bool frontier_exploration::FrontierSearch::isNewFrontierCell ( unsigned int  idx,
const std::vector< bool > &  frontier_flag 
) [protected]

isNewFrontierCell Evaluate if candidate cell is a valid candidate for a new frontier.

Parameters:
idxIndex of candidate cell
frontier_flagFlag vector indicating which cells are already marked as frontiers
Returns:

Definition at line 146 of file frontier_search.cpp.

Runs search implementation, outward from the start position.

Parameters:
positionInitial position to search from
Returns:
List of frontiers, if any

Definition at line 19 of file frontier_search.cpp.


Member Data Documentation

Definition at line 50 of file frontier_search.h.

Definition at line 51 of file frontier_search.h.

Definition at line 52 of file frontier_search.h.

Definition at line 52 of file frontier_search.h.


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


frontier_exploration
Author(s): Paul Bovbel
autogenerated on Fri Aug 28 2015 10:43:32