5 #include <geometry_msgs/Point.h> 6 #include <boost/foreach.hpp> 9 #include <frontier_exploration/Frontier.h> 21 std::list<Frontier> frontier_list;
26 ROS_ERROR(
"Robot out of costmap bounds, cannot search for frontiers");
31 boost::unique_lock < costmap_2d::Costmap2D::mutex_t > lock(*(
costmap_.
getMutex()));
39 std::vector<bool> visited_flag(
size_x_ * size_y_,
false);
42 std::queue<unsigned int> bfs;
50 ROS_WARN(
"Could not find nearby clear cell to start search");
52 visited_flag[bfs.front()] =
true;
55 unsigned int idx = bfs.front();
61 if(
map_[nbr] <=
map_[idx] && !visited_flag[nbr]){
62 visited_flag[nbr] =
true;
66 frontier_flag[nbr] =
true;
68 if(new_frontier.size > 1){
69 frontier_list.push_back(new_frontier);
83 output.centroid.x = 0;
84 output.centroid.y = 0;
86 output.min_distance = std::numeric_limits<double>::infinity();
94 std::queue<unsigned int> bfs;
95 bfs.push(initial_cell);
99 double reference_x, reference_y;
104 unsigned int idx = bfs.front();
113 frontier_flag[nbr] =
true;
123 output.centroid.x += wx;
124 output.centroid.y += wy;
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;
141 output.centroid.x /= output.size;
142 output.centroid.y /= output.size;
149 if(
map_[idx] != NO_INFORMATION || frontier_flag[idx]){
155 if(
map_[nbr] == FREE_SPACE){
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.
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
bool nearestCell(unsigned int &result, unsigned int start, unsigned char val, const costmap_2d::Costmap2D &costmap)
Find nearest cell of a specified value.
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.
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
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
unsigned int getIndex(unsigned int mx, unsigned int my) const