45 int deltax = abs(x1 - x0);
46 int deltay = abs(y1 - y0);
50 int xinc1, xinc2, yinc1, yinc2;
51 int den, num, numadd, numpixels;
96 for (
int curpixel = 0; curpixel <= numpixels; curpixel++)
119 while (i < footprint.size() - 1) {
120 if (footprint[i].x > footprint[i + 1].x) {
122 footprint[i] = footprint[i + 1];
123 footprint[i + 1] =
swap;
135 unsigned int min_x = footprint[0].
x;
136 unsigned int max_x = footprint[footprint.size() -1].x;
138 for (
unsigned int x = min_x; x <= max_x; ++x) {
139 if (i >= footprint.size() - 1) {
142 if (footprint[i].y < footprint[i + 1].y) {
143 min_pt = footprint[i];
144 max_pt = footprint[i + 1];
146 min_pt = footprint[i + 1];
147 max_pt = footprint[i];
151 while (i < footprint.size() && footprint[i].x == x) {
152 if(footprint[i].y < min_pt.
y) {
153 min_pt = footprint[i];
154 }
else if(footprint[i].y > max_pt.
y) {
155 max_pt = footprint[i];
161 for (
unsigned int y = min_pt.
y; y < max_pt.
y; ++y) {
164 footprint.push_back(pt);
172 static const std::vector<Cell>&
clearAndReturn(std::vector<Cell>& _cells)
182 const std::vector<geometry_msgs::Point>& footprint_spec,
185 std::vector<Cell> footprint_cells;
188 if (footprint_spec.size() <= 1) {
194 footprint_cells.push_back(center);
196 return footprint_cells;
200 double cos_th = cos(theta);
201 double sin_th = sin(theta);
203 unsigned int x0, y0, x1, y1;
204 unsigned int last_index = footprint_spec.size() - 1;
206 for (
unsigned int i = 0; i < last_index; ++i) {
208 new_x = x + (footprint_spec[i].x * cos_th - footprint_spec[i].y * sin_th);
209 new_y = y + (footprint_spec[i].x * sin_th + footprint_spec[i].y * cos_th);
210 if(!costmap.
worldToMap(new_x, new_y, x0, y0)) {
215 new_x = x + (footprint_spec[i + 1].x * cos_th - footprint_spec[i + 1].y * sin_th);
216 new_y = y + (footprint_spec[i + 1].x * sin_th + footprint_spec[i + 1].y * cos_th);
217 if (!costmap.
worldToMap(new_x, new_y, x1, y1)) {
225 new_x = x + (footprint_spec[last_index].x * cos_th - footprint_spec[last_index].y * sin_th);
226 new_y = y + (footprint_spec[last_index].x * sin_th + footprint_spec[last_index].y * cos_th);
227 if (!costmap.
worldToMap(new_x, new_y, x0, y0)) {
230 new_x = x + (footprint_spec[0].x * cos_th - footprint_spec[0].y * sin_th);
231 new_y = y + (footprint_spec[0].x * sin_th + footprint_spec[0].y * cos_th);
232 if(!costmap.
worldToMap(new_x, new_y, x1, y1)) {
242 return footprint_cells;