Thread-safe implementation of a frontier-search task for an input costmap. More...
#include <frontier_search.h>
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::Costmap2D & | costmap_ |
unsigned char * | map_ |
unsigned int | size_x_ |
unsigned int | size_y_ |
Thread-safe implementation of a frontier-search task for an input costmap.
Definition at line 12 of file frontier_search.h.
Constructor for search task.
costmap | Reference to costmap data to search. |
Definition at line 17 of file frontier_search.cpp.
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.
initial_cell | Index of cell to start frontier building |
reference | Reference index to calculate position from |
frontier_flag | Flag vector indicating which cells are already marked as frontiers |
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.
idx | Index of candidate cell |
frontier_flag | Flag vector indicating which cells are already marked as frontiers |
Definition at line 146 of file frontier_search.cpp.
std::list< Frontier > frontier_exploration::FrontierSearch::searchFrom | ( | geometry_msgs::Point | position | ) |
Runs search implementation, outward from the start position.
position | Initial position to search from |
Definition at line 19 of file frontier_search.cpp.
Definition at line 50 of file frontier_search.h.
unsigned char* frontier_exploration::FrontierSearch::map_ [private] |
Definition at line 51 of file frontier_search.h.
unsigned int frontier_exploration::FrontierSearch::size_x_ [private] |
Definition at line 52 of file frontier_search.h.
unsigned int frontier_exploration::FrontierSearch::size_y_ [private] |
Definition at line 52 of file frontier_search.h.