frontier_search.cpp
Go to the documentation of this file.
2 
5 #include <geometry_msgs/Point.h>
6 #include <boost/foreach.hpp>
7 
9 #include <frontier_exploration/Frontier.h>
10 
11 namespace frontier_exploration{
12 
16 
17 FrontierSearch::FrontierSearch(costmap_2d::Costmap2D &costmap) : costmap_(costmap) { }
18 
19 std::list<Frontier> FrontierSearch::searchFrom(geometry_msgs::Point position){
20 
21  std::list<Frontier> frontier_list;
22 
23  //Sanity check that robot is inside costmap bounds before searching
24  unsigned int mx,my;
25  if (!costmap_.worldToMap(position.x,position.y,mx,my)){
26  ROS_ERROR("Robot out of costmap bounds, cannot search for frontiers");
27  return frontier_list;
28  }
29 
30  //make sure map is consistent and locked for duration of search
31  boost::unique_lock < costmap_2d::Costmap2D::mutex_t > lock(*(costmap_.getMutex()));
32 
36 
37  //initialize flag arrays to keep track of visited and frontier cells
38  std::vector<bool> frontier_flag(size_x_ * size_y_, false);
39  std::vector<bool> visited_flag(size_x_ * size_y_, false);
40 
41  //initialize breadth first search
42  std::queue<unsigned int> bfs;
43 
44  //find closest clear cell to start search
45  unsigned int clear, pos = costmap_.getIndex(mx,my);
46  if(nearestCell(clear, pos, FREE_SPACE, costmap_)){
47  bfs.push(clear);
48  }else{
49  bfs.push(pos);
50  ROS_WARN("Could not find nearby clear cell to start search");
51  }
52  visited_flag[bfs.front()] = true;
53 
54  while(!bfs.empty()){
55  unsigned int idx = bfs.front();
56  bfs.pop();
57 
58  //iterate over 4-connected neighbourhood
59  BOOST_FOREACH(unsigned nbr, nhood4(idx, costmap_)){
60  //add to queue all free, unvisited cells, use descending search in case initialized on non-free cell
61  if(map_[nbr] <= map_[idx] && !visited_flag[nbr]){
62  visited_flag[nbr] = true;
63  bfs.push(nbr);
64  //check if cell is new frontier cell (unvisited, NO_INFORMATION, free neighbour)
65  }else if(isNewFrontierCell(nbr, frontier_flag)){
66  frontier_flag[nbr] = true;
67  Frontier new_frontier = buildNewFrontier(nbr, pos, frontier_flag);
68  if(new_frontier.size > 1){
69  frontier_list.push_back(new_frontier);
70  }
71  }
72  }
73  }
74 
75  return frontier_list;
76 
77 }
78 
79 Frontier FrontierSearch::buildNewFrontier(unsigned int initial_cell, unsigned int reference, std::vector<bool>& frontier_flag){
80 
81  //initialize frontier structure
82  Frontier output;
83  output.centroid.x = 0;
84  output.centroid.y = 0;
85  output.size = 1;
86  output.min_distance = std::numeric_limits<double>::infinity();
87 
88  //record initial contact point for frontier
89  unsigned int ix, iy;
90  costmap_.indexToCells(initial_cell,ix,iy);
91  costmap_.mapToWorld(ix,iy,output.initial.x,output.initial.y);
92 
93  //push initial gridcell onto queue
94  std::queue<unsigned int> bfs;
95  bfs.push(initial_cell);
96 
97  //cache reference position in world coords
98  unsigned int rx,ry;
99  double reference_x, reference_y;
100  costmap_.indexToCells(reference,rx,ry);
101  costmap_.mapToWorld(rx,ry,reference_x,reference_y);
102 
103  while(!bfs.empty()){
104  unsigned int idx = bfs.front();
105  bfs.pop();
106 
107  //try adding cells in 8-connected neighborhood to frontier
108  BOOST_FOREACH(unsigned int nbr, nhood8(idx, costmap_)){
109  //check if neighbour is a potential frontier cell
110  if(isNewFrontierCell(nbr,frontier_flag)){
111 
112  //mark cell as frontier
113  frontier_flag[nbr] = true;
114  unsigned int mx,my;
115  double wx,wy;
116  costmap_.indexToCells(nbr,mx,my);
117  costmap_.mapToWorld(mx,my,wx,wy);
118 
119  //update frontier size
120  output.size++;
121 
122  //update centroid of frontier
123  output.centroid.x += wx;
124  output.centroid.y += wy;
125 
126  //determine frontier's distance from robot, going by closest gridcell to robot
127  double distance = sqrt(pow((double(reference_x)-double(wx)),2.0) + pow((double(reference_y)-double(wy)),2.0));
128  if(distance < output.min_distance){
129  output.min_distance = distance;
130  output.middle.x = wx;
131  output.middle.y = wy;
132  }
133 
134  //add to queue for breadth first search
135  bfs.push(nbr);
136  }
137  }
138  }
139 
140  //average out frontier centroid
141  output.centroid.x /= output.size;
142  output.centroid.y /= output.size;
143  return output;
144 }
145 
146 bool FrontierSearch::isNewFrontierCell(unsigned int idx, const std::vector<bool>& frontier_flag){
147 
148  //check that cell is unknown and not already marked as frontier
149  if(map_[idx] != NO_INFORMATION || frontier_flag[idx]){
150  return false;
151  }
152 
153  //frontier cells should have at least one cell in 4-connected neighbourhood that is free
154  BOOST_FOREACH(unsigned int nbr, nhood4(idx, costmap_)){
155  if(map_[nbr] == FREE_SPACE){
156  return true;
157  }
158  }
159 
160  return false;
161 
162 }
163 
164 }
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
std::vector< unsigned int > nhood4(unsigned int idx, const costmap_2d::Costmap2D &costmap)
Determine 4-connected neighbourhood of an input cell, checking for map edges.
Definition: costmap_tools.h:18
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_
static const unsigned char FREE_SPACE
#define ROS_WARN(...)
bool nearestCell(unsigned int &result, unsigned int start, unsigned char val, const costmap_2d::Costmap2D &costmap)
Find nearest cell of a specified value.
Definition: costmap_tools.h:86
unsigned char * getCharMap() const
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.
double distance(double x0, double y0, double x1, double y1)
std::vector< unsigned int > nhood8(unsigned int idx, const costmap_2d::Costmap2D &costmap)
Determine 8-connected neighbourhood of an input cell, checking for map edges.
Definition: costmap_tools.h:51
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.
unsigned int getSizeInCellsY() const
unsigned int getSizeInCellsX() const
static const unsigned char LETHAL_OBSTACLE
static const unsigned char NO_INFORMATION
void indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const
#define ROS_ERROR(...)
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
unsigned int getIndex(unsigned int mx, unsigned int my) const


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