Public Member Functions | Protected Member Functions | Private Attributes | List of all members
frontier_exploration::FrontierSearch Class Reference

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

#include <frontier_search.h>

Public Member Functions

 FrontierSearch ()
 
 FrontierSearch (costmap_2d::Costmap2D *costmap, double potential_scale, double gain_scale, double min_frontier_size)
 Constructor for search task. More...
 
std::vector< FrontiersearchFrom (geometry_msgs::Point position)
 Runs search implementation, outward from the start position. More...
 

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. More...
 
double frontierCost (const Frontier &frontier)
 computes frontier cost More...
 
bool isNewFrontierCell (unsigned int idx, const std::vector< bool > &frontier_flag)
 isNewFrontierCell Evaluate if candidate cell is a valid candidate for a new frontier. More...
 

Private Attributes

costmap_2d::Costmap2Dcostmap_
 
double gain_scale_
 
unsigned char * map_
 
double min_frontier_size_
 
double potential_scale_
 
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 26 of file frontier_search.h.

Constructor & Destructor Documentation

frontier_exploration::FrontierSearch::FrontierSearch ( )
inline

Definition at line 29 of file frontier_search.h.

frontier_exploration::FrontierSearch::FrontierSearch ( costmap_2d::Costmap2D costmap,
double  potential_scale,
double  gain_scale,
double  min_frontier_size 
)

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
new frontier

Definition at line 97 of file frontier_search.cpp.

double frontier_exploration::FrontierSearch::frontierCost ( const Frontier frontier)
protected

computes frontier cost

cost function is defined by potential_scale and gain_scale

Parameters
frontierfrontier for which compute the cost
Returns
cost of the frontier

Definition at line 191 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
true if the cell is frontier cell

Definition at line 172 of file frontier_search.cpp.

std::vector< Frontier > frontier_exploration::FrontierSearch::searchFrom ( geometry_msgs::Point  position)

Runs search implementation, outward from the start position.

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

Definition at line 27 of file frontier_search.cpp.

Member Data Documentation

costmap_2d::Costmap2D* frontier_exploration::FrontierSearch::costmap_
private

Definition at line 81 of file frontier_search.h.

double frontier_exploration::FrontierSearch::gain_scale_
private

Definition at line 84 of file frontier_search.h.

unsigned char* frontier_exploration::FrontierSearch::map_
private

Definition at line 82 of file frontier_search.h.

double frontier_exploration::FrontierSearch::min_frontier_size_
private

Definition at line 85 of file frontier_search.h.

double frontier_exploration::FrontierSearch::potential_scale_
private

Definition at line 84 of file frontier_search.h.

unsigned int frontier_exploration::FrontierSearch::size_x_
private

Definition at line 83 of file frontier_search.h.

unsigned int frontier_exploration::FrontierSearch::size_y_
private

Definition at line 83 of file frontier_search.h.


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


explore
Author(s): Jiri Horner
autogenerated on Mon Jun 10 2019 13:56:49