frontier_search.h
Go to the documentation of this file.
1 #ifndef FRONTIER_SEARCH_H_
2 #define FRONTIER_SEARCH_H_
3 
4 #include <frontier_exploration/Frontier.h>
6 
7 namespace frontier_exploration{
8 
13 
14 public:
15 
21 
27  std::list<Frontier> searchFrom(geometry_msgs::Point position);
28 
29 protected:
30 
38  Frontier buildNewFrontier(unsigned int initial_cell, unsigned int reference, std::vector<bool>& frontier_flag);
39 
46  bool isNewFrontierCell(unsigned int idx, const std::vector<bool>& frontier_flag);
47 
48 private:
49 
51  unsigned char* map_;
52  unsigned int size_x_ , size_y_;
53 
54 };
55 
56 }
57 #endif
bool isNewFrontierCell(unsigned int idx, const std::vector< bool > &frontier_flag)
isNewFrontierCell Evaluate if candidate cell is a valid candidate for a new frontier.
costmap_2d::Costmap2D & costmap_
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.
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.
Thread-safe implementation of a frontier-search task for an input costmap.


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