frontier_search.h
Go to the documentation of this file.
1 #ifndef FRONTIER_SEARCH_H_
2 #define FRONTIER_SEARCH_H_
3 
5 
6 namespace frontier_exploration
7 {
12 struct Frontier {
13  std::uint32_t size;
14  double min_distance;
15  double cost;
16  geometry_msgs::Point initial;
17  geometry_msgs::Point centroid;
18  geometry_msgs::Point middle;
19  std::vector<geometry_msgs::Point> points;
20 };
21 
27 {
28 public:
30  {
31  }
32 
37  FrontierSearch(costmap_2d::Costmap2D* costmap, double potential_scale,
38  double gain_scale, double min_frontier_size);
39 
45  std::vector<Frontier> searchFrom(geometry_msgs::Point position);
46 
47 protected:
57  Frontier buildNewFrontier(unsigned int initial_cell, unsigned int reference,
58  std::vector<bool>& frontier_flag);
59 
68  bool isNewFrontierCell(unsigned int idx,
69  const std::vector<bool>& frontier_flag);
70 
78  double frontierCost(const Frontier& frontier);
79 
80 private:
82  unsigned char* map_;
83  unsigned int size_x_, size_y_;
84  double potential_scale_, gain_scale_;
86 };
87 }
88 #endif
geometry_msgs::Point centroid
geometry_msgs::Point initial
Represents a frontier.
std::vector< geometry_msgs::Point > points
Thread-safe implementation of a frontier-search task for an input costmap.
costmap_2d::Costmap2D * costmap_
geometry_msgs::Point middle


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