-
Notifications
You must be signed in to change notification settings - Fork 1.3k
/
costmap_2d.cpp
568 lines (483 loc) · 15.7 KB
/
costmap_2d.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
/*********************************************************************
*
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, 2013, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
* Author: Eitan Marder-Eppstein
* David V. Lu!!
*********************************************************************/
#include "nav2_costmap_2d/costmap_2d.hpp"
#include <algorithm>
#include <cstdio>
#include <string>
#include <vector>
#include "nav2_costmap_2d/cost_values.hpp"
#include "nav2_util/occ_grid_values.hpp"
namespace nav2_costmap_2d
{
Costmap2D::Costmap2D(
unsigned int cells_size_x, unsigned int cells_size_y, double resolution,
double origin_x, double origin_y, unsigned char default_value)
: resolution_(resolution), origin_x_(origin_x),
origin_y_(origin_y), costmap_(NULL), default_value_(default_value)
{
access_ = new mutex_t();
// create the costmap
initMaps(cells_size_x, cells_size_y);
resetMaps();
}
Costmap2D::Costmap2D(const nav_msgs::msg::OccupancyGrid & map)
: default_value_(FREE_SPACE)
{
access_ = new mutex_t();
// fill local variables
size_x_ = map.info.width;
size_y_ = map.info.height;
resolution_ = map.info.resolution;
origin_x_ = map.info.origin.position.x;
origin_y_ = map.info.origin.position.y;
// create the costmap
costmap_ = new unsigned char[size_x_ * size_y_];
// fill the costmap with a data
int8_t data;
for (unsigned int it = 0; it < size_x_ * size_y_; it++) {
data = map.data[it];
if (data == nav2_util::OCC_GRID_UNKNOWN) {
costmap_[it] = NO_INFORMATION;
} else {
// Linear conversion from OccupancyGrid data range [OCC_GRID_FREE..OCC_GRID_OCCUPIED]
// to costmap data range [FREE_SPACE..LETHAL_OBSTACLE]
costmap_[it] = std::round(
static_cast<double>(data) * (LETHAL_OBSTACLE - FREE_SPACE) /
(nav2_util::OCC_GRID_OCCUPIED - nav2_util::OCC_GRID_FREE));
}
}
}
void Costmap2D::deleteMaps()
{
// clean up data
std::unique_lock<mutex_t> lock(*access_);
delete[] costmap_;
costmap_ = NULL;
}
void Costmap2D::initMaps(unsigned int size_x, unsigned int size_y)
{
std::unique_lock<mutex_t> lock(*access_);
delete[] costmap_;
size_x_ = size_x;
size_y_ = size_y;
costmap_ = new unsigned char[size_x * size_y];
}
void Costmap2D::resizeMap(
unsigned int size_x, unsigned int size_y, double resolution,
double origin_x, double origin_y)
{
resolution_ = resolution;
origin_x_ = origin_x;
origin_y_ = origin_y;
initMaps(size_x, size_y);
// reset our maps to have no information
resetMaps();
}
void Costmap2D::resetMaps()
{
std::unique_lock<mutex_t> lock(*access_);
memset(costmap_, default_value_, size_x_ * size_y_ * sizeof(unsigned char));
}
void Costmap2D::resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
{
resetMapToValue(x0, y0, xn, yn, default_value_);
}
void Costmap2D::resetMapToValue(
unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn, unsigned char value)
{
std::unique_lock<mutex_t> lock(*(access_));
unsigned int len = xn - x0;
for (unsigned int y = y0 * size_x_ + x0; y < yn * size_x_ + x0; y += size_x_) {
memset(costmap_ + y, value, len * sizeof(unsigned char));
}
}
bool Costmap2D::copyCostmapWindow(
const Costmap2D & map, double win_origin_x, double win_origin_y,
double win_size_x,
double win_size_y)
{
// check for self windowing
if (this == &map) {
// ROS_ERROR("Cannot convert this costmap into a window of itself");
return false;
}
// clean up old data
deleteMaps();
// compute the bounds of our new map
unsigned int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
if (!map.worldToMap(win_origin_x, win_origin_y, lower_left_x, lower_left_y) ||
!map.worldToMap(
win_origin_x + win_size_x, win_origin_y + win_size_y, upper_right_x,
upper_right_y))
{
// ROS_ERROR("Cannot window a map that the window bounds don't fit inside of");
return false;
}
resolution_ = map.resolution_;
origin_x_ = win_origin_x;
origin_y_ = win_origin_y;
// initialize our various maps and reset markers for inflation
initMaps(upper_right_x - lower_left_x, upper_right_y - lower_left_y);
// copy the window of the static map and the costmap that we're taking
copyMapRegion(
map.costmap_, lower_left_x, lower_left_y, map.size_x_, costmap_, 0, 0, size_x_,
size_x_,
size_y_);
return true;
}
bool Costmap2D::copyWindow(
const Costmap2D & source,
unsigned int sx0, unsigned int sy0, unsigned int sxn, unsigned int syn,
unsigned int dx0, unsigned int dy0)
{
const unsigned int sz_x = sxn - sx0;
const unsigned int sz_y = syn - sy0;
if (sxn > source.getSizeInCellsX() || syn > source.getSizeInCellsY()) {
return false;
}
if (dx0 + sz_x > size_x_ || dy0 + sz_y > size_y_) {
return false;
}
copyMapRegion(
source.costmap_, sx0, sy0, source.size_x_,
costmap_, dx0, dy0, size_x_,
sz_x, sz_y);
return true;
}
Costmap2D & Costmap2D::operator=(const Costmap2D & map)
{
// check for self assignement
if (this == &map) {
return *this;
}
// clean up old data
deleteMaps();
size_x_ = map.size_x_;
size_y_ = map.size_y_;
resolution_ = map.resolution_;
origin_x_ = map.origin_x_;
origin_y_ = map.origin_y_;
// initialize our various maps
initMaps(size_x_, size_y_);
// copy the cost map
memcpy(costmap_, map.costmap_, size_x_ * size_y_ * sizeof(unsigned char));
return *this;
}
Costmap2D::Costmap2D(const Costmap2D & map)
: costmap_(NULL)
{
access_ = new mutex_t();
*this = map;
}
// just initialize everything to NULL by default
Costmap2D::Costmap2D()
: size_x_(0), size_y_(0), resolution_(0.0), origin_x_(0.0), origin_y_(0.0), costmap_(NULL)
{
access_ = new mutex_t();
}
Costmap2D::~Costmap2D()
{
deleteMaps();
delete access_;
}
unsigned int Costmap2D::cellDistance(double world_dist)
{
double cells_dist = std::max(0.0, ceil(world_dist / resolution_));
return (unsigned int)cells_dist;
}
unsigned char * Costmap2D::getCharMap() const
{
return costmap_;
}
unsigned char Costmap2D::getCost(unsigned int mx, unsigned int my) const
{
return costmap_[getIndex(mx, my)];
}
unsigned char Costmap2D::getCost(unsigned int undex) const
{
return costmap_[undex];
}
void Costmap2D::setCost(unsigned int mx, unsigned int my, unsigned char cost)
{
costmap_[getIndex(mx, my)] = cost;
}
void Costmap2D::mapToWorld(unsigned int mx, unsigned int my, double & wx, double & wy) const
{
wx = origin_x_ + (mx + 0.5) * resolution_;
wy = origin_y_ + (my + 0.5) * resolution_;
}
bool Costmap2D::worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my) const
{
if (wx < origin_x_ || wy < origin_y_) {
return false;
}
mx = static_cast<unsigned int>((wx - origin_x_) / resolution_);
my = static_cast<unsigned int>((wy - origin_y_) / resolution_);
if (mx < size_x_ && my < size_y_) {
return true;
}
return false;
}
bool Costmap2D::worldToMapContinuous(double wx, double wy, float & mx, float & my) const
{
if (wx < origin_x_ || wy < origin_y_) {
return false;
}
mx = static_cast<float>((wx - origin_x_) / resolution_) + 0.5f;
my = static_cast<float>((wy - origin_y_) / resolution_) + 0.5f;
if (mx < size_x_ && my < size_y_) {
return true;
}
return false;
}
void Costmap2D::worldToMapNoBounds(double wx, double wy, int & mx, int & my) const
{
mx = static_cast<int>((wx - origin_x_) / resolution_);
my = static_cast<int>((wy - origin_y_) / resolution_);
}
void Costmap2D::worldToMapEnforceBounds(double wx, double wy, int & mx, int & my) const
{
// Here we avoid doing any math to wx,wy before comparing them to
// the bounds, so their values can go out to the max and min values
// of double floating point.
if (wx < origin_x_) {
mx = 0;
} else if (wx > resolution_ * size_x_ + origin_x_) {
mx = size_x_ - 1;
} else {
mx = static_cast<int>((wx - origin_x_) / resolution_);
}
if (wy < origin_y_) {
my = 0;
} else if (wy > resolution_ * size_y_ + origin_y_) {
my = size_y_ - 1;
} else {
my = static_cast<int>((wy - origin_y_) / resolution_);
}
}
void Costmap2D::updateOrigin(double new_origin_x, double new_origin_y)
{
// project the new origin into the grid
int cell_ox, cell_oy;
cell_ox = static_cast<int>((new_origin_x - origin_x_) / resolution_);
cell_oy = static_cast<int>((new_origin_y - origin_y_) / resolution_);
// compute the associated world coordinates for the origin cell
// because we want to keep things grid-aligned
double new_grid_ox, new_grid_oy;
new_grid_ox = origin_x_ + cell_ox * resolution_;
new_grid_oy = origin_y_ + cell_oy * resolution_;
// To save casting from unsigned int to int a bunch of times
int size_x = size_x_;
int size_y = size_y_;
// we need to compute the overlap of the new and existing windows
int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
lower_left_x = std::min(std::max(cell_ox, 0), size_x);
lower_left_y = std::min(std::max(cell_oy, 0), size_y);
upper_right_x = std::min(std::max(cell_ox + size_x, 0), size_x);
upper_right_y = std::min(std::max(cell_oy + size_y, 0), size_y);
unsigned int cell_size_x = upper_right_x - lower_left_x;
unsigned int cell_size_y = upper_right_y - lower_left_y;
// we need a map to store the obstacles in the window temporarily
unsigned char * local_map = new unsigned char[cell_size_x * cell_size_y];
// copy the local window in the costmap to the local map
copyMapRegion(
costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x,
cell_size_x,
cell_size_y);
// now we'll set the costmap to be completely unknown if we track unknown space
resetMaps();
// update the origin with the appropriate world coordinates
origin_x_ = new_grid_ox;
origin_y_ = new_grid_oy;
// compute the starting cell location for copying data back in
int start_x = lower_left_x - cell_ox;
int start_y = lower_left_y - cell_oy;
// now we want to copy the overlapping information back into the map, but in its new location
copyMapRegion(
local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x,
cell_size_y);
// make sure to clean up
delete[] local_map;
}
bool Costmap2D::setConvexPolygonCost(
const std::vector<geometry_msgs::msg::Point> & polygon,
unsigned char cost_value)
{
// we assume the polygon is given in the global_frame...
// we need to transform it to map coordinates
std::vector<MapLocation> map_polygon;
for (unsigned int i = 0; i < polygon.size(); ++i) {
MapLocation loc;
if (!worldToMap(polygon[i].x, polygon[i].y, loc.x, loc.y)) {
// ("Polygon lies outside map bounds, so we can't fill it");
return false;
}
map_polygon.push_back(loc);
}
std::vector<MapLocation> polygon_cells;
// get the cells that fill the polygon
convexFillCells(map_polygon, polygon_cells);
// set the cost of those cells
for (unsigned int i = 0; i < polygon_cells.size(); ++i) {
unsigned int index = getIndex(polygon_cells[i].x, polygon_cells[i].y);
costmap_[index] = cost_value;
}
return true;
}
void Costmap2D::polygonOutlineCells(
const std::vector<MapLocation> & polygon,
std::vector<MapLocation> & polygon_cells)
{
PolygonOutlineCells cell_gatherer(*this, costmap_, polygon_cells);
for (unsigned int i = 0; i < polygon.size() - 1; ++i) {
raytraceLine(cell_gatherer, polygon[i].x, polygon[i].y, polygon[i + 1].x, polygon[i + 1].y);
}
if (!polygon.empty()) {
unsigned int last_index = polygon.size() - 1;
// we also need to close the polygon by going from the last point to the first
raytraceLine(
cell_gatherer, polygon[last_index].x, polygon[last_index].y, polygon[0].x,
polygon[0].y);
}
}
void Costmap2D::convexFillCells(
const std::vector<MapLocation> & polygon,
std::vector<MapLocation> & polygon_cells)
{
// we need a minimum polygon of a triangle
if (polygon.size() < 3) {
return;
}
// first get the cells that make up the outline of the polygon
polygonOutlineCells(polygon, polygon_cells);
// quick bubble sort to sort points by x
MapLocation swap;
unsigned int i = 0;
while (i < polygon_cells.size() - 1) {
if (polygon_cells[i].x > polygon_cells[i + 1].x) {
swap = polygon_cells[i];
polygon_cells[i] = polygon_cells[i + 1];
polygon_cells[i + 1] = swap;
if (i > 0) {
--i;
}
} else {
++i;
}
}
i = 0;
MapLocation min_pt;
MapLocation max_pt;
unsigned int min_x = polygon_cells[0].x;
unsigned int max_x = polygon_cells[polygon_cells.size() - 1].x;
// walk through each column and mark cells inside the polygon
for (unsigned int x = min_x; x <= max_x; ++x) {
if (i >= polygon_cells.size() - 1) {
break;
}
if (polygon_cells[i].y < polygon_cells[i + 1].y) {
min_pt = polygon_cells[i];
max_pt = polygon_cells[i + 1];
} else {
min_pt = polygon_cells[i + 1];
max_pt = polygon_cells[i];
}
i += 2;
while (i < polygon_cells.size() && polygon_cells[i].x == x) {
if (polygon_cells[i].y < min_pt.y) {
min_pt = polygon_cells[i];
} else if (polygon_cells[i].y > max_pt.y) {
max_pt = polygon_cells[i];
}
++i;
}
MapLocation pt;
// loop though cells in the column
for (unsigned int y = min_pt.y; y <= max_pt.y; ++y) {
pt.x = x;
pt.y = y;
polygon_cells.push_back(pt);
}
}
}
unsigned int Costmap2D::getSizeInCellsX() const
{
return size_x_;
}
unsigned int Costmap2D::getSizeInCellsY() const
{
return size_y_;
}
double Costmap2D::getSizeInMetersX() const
{
return (size_x_ - 1 + 0.5) * resolution_;
}
double Costmap2D::getSizeInMetersY() const
{
return (size_y_ - 1 + 0.5) * resolution_;
}
double Costmap2D::getOriginX() const
{
return origin_x_;
}
double Costmap2D::getOriginY() const
{
return origin_y_;
}
double Costmap2D::getResolution() const
{
return resolution_;
}
bool Costmap2D::saveMap(std::string file_name)
{
FILE * fp = fopen(file_name.c_str(), "w");
if (!fp) {
return false;
}
fprintf(fp, "P2\n%u\n%u\n%u\n", size_x_, size_y_, 0xff);
for (unsigned int iy = 0; iy < size_y_; iy++) {
for (unsigned int ix = 0; ix < size_x_; ix++) {
unsigned char cost = getCost(ix, iy);
fprintf(fp, "%d ", cost);
}
fprintf(fp, "\n");
}
fclose(fp);
return true;
}
} // namespace nav2_costmap_2d