5 #include "nav_msgs/OccupancyGrid.h"
10 void update(nav_msgs::OccupancyGrid grid)
31 bool getIndex(
unsigned int x,
unsigned int y,
unsigned int &i)
63 bool setData(
unsigned int index,
signed char value)
75 signed char value =
getData(index);
85 if(
getData(x-1, y-1) == -1)
return true;
86 if(
getData(x-1, y ) == -1)
return true;
87 if(
getData(x-1, y+1) == -1)
return true;
88 if(
getData(x , y-1) == -1)
return true;
89 if(
getData(x , y+1) == -1)
return true;
90 if(
getData(x+1, y-1) == -1)
return true;
91 if(
getData(x+1, y ) == -1)
return true;
92 if(
getData(x+1, y+1) == -1)
return true;
100 std::vector<unsigned int> neighbors;
102 if(offset < 0) offset *= -1;
106 for(
int i = -offset; i <= offset; i++)
107 for(
int j = -offset; j <= offset; j++)
109 neighbors.push_back(index);
115 std::vector<unsigned int>
getNeighbors(
unsigned int index,
bool diagonal =
false)
117 std::vector<unsigned int> neighbors;
122 if(
getIndex(x-1,y, i)) neighbors.push_back(i);
123 if(
getIndex(x+1,y, i)) neighbors.push_back(i);
124 if(
getIndex(x, y-1,i)) neighbors.push_back(i);
125 if(
getIndex(x, y+1,i)) neighbors.push_back(i);
129 if(
getIndex(x-1,y-1,i)) neighbors.push_back(i);
130 if(
getIndex(x-1,y+1,i)) neighbors.push_back(i);
131 if(
getIndex(x+1,y-1,i)) neighbors.push_back(i);
132 if(
getIndex(x+1,y+1,i)) neighbors.push_back(i);
158 signed char value =
getData(x, y);