00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <costmap_2d/costmap_2d.h>
00038 #include <cstdio>
00039
00040 using namespace std;
00041
00042 namespace costmap_2d{
00043 Costmap2D::Costmap2D(unsigned int cells_size_x, unsigned int cells_size_y,
00044 double resolution, double origin_x, double origin_y, double inscribed_radius,
00045 double circumscribed_radius, double inflation_radius, double max_obstacle_range,
00046 double max_obstacle_height, double max_raytrace_range, double weight,
00047 const std::vector<unsigned char>& static_data, unsigned char lethal_threshold, bool track_unknown_space, unsigned char unknown_cost_value) : size_x_(cells_size_x),
00048 size_y_(cells_size_y), resolution_(resolution), origin_x_(origin_x), origin_y_(origin_y), static_map_(NULL),
00049 costmap_(NULL), markers_(NULL), max_obstacle_range_(max_obstacle_range),
00050 max_obstacle_height_(max_obstacle_height), max_raytrace_range_(max_raytrace_range), cached_costs_(NULL), cached_distances_(NULL),
00051 inscribed_radius_(inscribed_radius), circumscribed_radius_(circumscribed_radius), inflation_radius_(inflation_radius),
00052 weight_(weight), lethal_threshold_(lethal_threshold), track_unknown_space_(track_unknown_space), unknown_cost_value_(unknown_cost_value), inflation_queue_(){
00053
00054 costmap_ = new unsigned char[size_x_ * size_y_];
00055 static_map_ = new unsigned char[size_x_ * size_y_];
00056 markers_ = new unsigned char[size_x_ * size_y_];
00057 memset(markers_, 0, size_x_ * size_y_ * sizeof(unsigned char));
00058
00059
00060 cell_inscribed_radius_ = cellDistance(inscribed_radius);
00061 cell_circumscribed_radius_ = cellDistance(circumscribed_radius);
00062 cell_inflation_radius_ = cellDistance(inflation_radius);
00063
00064
00065 circumscribed_cost_lb_ = computeCost(cell_circumscribed_radius_);
00066
00067
00068 cached_costs_ = new unsigned char*[cell_inflation_radius_ + 2];
00069 cached_distances_ = new double*[cell_inflation_radius_ + 2];
00070 for(unsigned int i = 0; i <= cell_inflation_radius_ + 1; ++i){
00071 cached_costs_[i] = new unsigned char[cell_inflation_radius_ + 2];
00072 cached_distances_[i] = new double[cell_inflation_radius_ + 2];
00073 for(unsigned int j = 0; j <= cell_inflation_radius_ + 1; ++j){
00074 cached_distances_[i][j] = sqrt(i*i + j*j);
00075 cached_costs_[i][j] = computeCost(cached_distances_[i][j]);
00076 }
00077 }
00078
00079 if(!static_data.empty()){
00080 ROS_ASSERT_MSG(size_x_ * size_y_ == static_data.size(), "If you want to initialize a costmap with static data, their sizes must match.");
00081
00082
00083 ROS_ASSERT_MSG(inflation_queue_.empty(), "The inflation queue must be empty at the beginning of inflation");
00084
00085 unsigned int index = 0;
00086 unsigned char* costmap_index = costmap_;
00087 std::vector<unsigned char>::const_iterator static_data_index = static_data.begin();
00088
00089
00090 for(unsigned int i = 0; i < size_y_; ++i){
00091 for(unsigned int j = 0; j < size_x_; ++j){
00092
00093 if(track_unknown_space_ && unknown_cost_value_ > 0 && *static_data_index == unknown_cost_value_)
00094 *costmap_index = NO_INFORMATION;
00095 else if(*static_data_index >= lethal_threshold_)
00096 *costmap_index = LETHAL_OBSTACLE;
00097 else
00098 *costmap_index = FREE_SPACE;
00099
00100 if(*costmap_index == LETHAL_OBSTACLE){
00101 unsigned int mx, my;
00102 indexToCells(index, mx, my);
00103 enqueue(index, mx, my, mx, my, inflation_queue_);
00104 }
00105
00106 ++costmap_index;
00107 ++static_data_index;
00108 ++index;
00109 }
00110 }
00111
00112
00113 inflateObstacles(inflation_queue_);
00114
00115
00116 memcpy(static_map_, costmap_, size_x_ * size_y_ * sizeof(unsigned char));
00117 }
00118 else{
00119
00120 resetMaps();
00121 }
00122 }
00123
00124 void Costmap2D::replaceFullMap(double win_origin_x, double win_origin_y,
00125 unsigned int data_size_x, unsigned int data_size_y,
00126 const std::vector<unsigned char>& static_data){
00127
00128 deleteMaps();
00129
00130
00131 size_x_ = data_size_x;
00132 size_y_ = data_size_y;
00133 origin_x_ = win_origin_x;
00134 origin_y_ = win_origin_y;
00135
00136
00137 initMaps(size_x_, size_y_);
00138
00139
00140 ROS_ASSERT_MSG(inflation_queue_.empty(), "The inflation queue must be empty at the beginning of inflation");
00141
00142 unsigned int index = 0;
00143 unsigned char* costmap_index = costmap_;
00144 std::vector<unsigned char>::const_iterator static_data_index = static_data.begin();
00145
00146
00147 for(unsigned int i = 0; i < size_y_; ++i){
00148 for(unsigned int j = 0; j < size_x_; ++j){
00149
00150 if(track_unknown_space_ && unknown_cost_value_ > 0 && *static_data_index == unknown_cost_value_)
00151 *costmap_index = NO_INFORMATION;
00152 else if(*static_data_index >= lethal_threshold_)
00153 *costmap_index = LETHAL_OBSTACLE;
00154 else
00155 *costmap_index = FREE_SPACE;
00156
00157 if(*costmap_index == LETHAL_OBSTACLE){
00158 unsigned int mx, my;
00159 indexToCells(index, mx, my);
00160 enqueue(index, mx, my, mx, my, inflation_queue_);
00161 }
00162 ++costmap_index;
00163 ++static_data_index;
00164 ++index;
00165 }
00166 }
00167
00168
00169 inflateObstacles(inflation_queue_);
00170
00171
00172 memcpy(static_map_, costmap_, size_x_ * size_y_ * sizeof(unsigned char));
00173 }
00174
00175 void Costmap2D::replaceStaticMapWindow(double win_origin_x, double win_origin_y,
00176 unsigned int data_size_x, unsigned int data_size_y,
00177 const std::vector<unsigned char>& static_data){
00178 unsigned int start_x, start_y;
00179 if(!worldToMap(win_origin_x, win_origin_y, start_x, start_y) || (start_x + data_size_x) > size_x_ || (start_y + data_size_y) > size_y_){
00180 ROS_ERROR("You must call replaceStaticMapWindow with a window origin and size that is contained within the map");
00181 return;
00182 }
00183
00184
00185 unsigned int max_inflation_change = 2 * cell_inflation_radius_;
00186
00187
00188 unsigned int copy_sx = std::min(std::max(0, (int)start_x - (int)max_inflation_change), (int)size_x_);
00189 unsigned int copy_sy = std::min(std::max(0, (int)start_y - (int)max_inflation_change), (int)size_x_);
00190 unsigned int copy_ex = std::max(std::min((int)size_x_, (int)start_x + (int)data_size_x + (int)max_inflation_change), 0);
00191 unsigned int copy_ey = std::max(std::min((int)size_y_, (int)start_y + (int)data_size_y + (int)max_inflation_change), 0);
00192
00193 unsigned int copy_size_x = copy_ex - copy_sx;
00194 unsigned int copy_size_y = copy_ey - copy_sy;
00195
00196
00197 double ll_x, ll_y, ur_x, ur_y;
00198 mapToWorld(copy_sx, copy_sy, ll_x, ll_y);
00199 mapToWorld(copy_ex, copy_ey, ur_x, ur_y);
00200 double mid_x = (ll_x + ur_x) / 2;
00201 double mid_y = (ll_y + ur_y) / 2;
00202 double size_x = ur_x - ll_x;
00203 double size_y = ur_y - ll_y;
00204
00205
00206
00207 clearNonLethal(mid_x, mid_y, size_x, size_y);
00208
00209
00210 unsigned int start_index = start_y * size_x_ + start_x;
00211 unsigned char* costmap_index = costmap_ + start_index;
00212 std::vector<unsigned char>::const_iterator static_data_index = static_data.begin();
00213 for(unsigned int i = 0; i < data_size_y; ++i){
00214 for(unsigned int j = 0; j < data_size_x; ++j){
00215
00216 if(track_unknown_space_ && unknown_cost_value_ > 0 && *static_data_index == unknown_cost_value_)
00217 *costmap_index = NO_INFORMATION;
00218 else if(*static_data_index >= lethal_threshold_)
00219 *costmap_index = LETHAL_OBSTACLE;
00220 else
00221 *costmap_index = FREE_SPACE;
00222
00223 ++costmap_index;
00224 ++static_data_index;
00225 }
00226 costmap_index += size_x_ - data_size_x;
00227 }
00228
00229
00230
00231
00232 reinflateWindow(mid_x, mid_y, size_x, size_y, false);
00233
00234
00235
00236 copyMapRegion(costmap_, copy_sx, copy_sy, size_x_, static_map_, copy_sx, copy_sy, size_x_, copy_size_x, copy_size_y);
00237
00238 }
00239
00240 void Costmap2D::reshapeStaticMap(double win_origin_x, double win_origin_y,
00241 unsigned int data_size_x, unsigned int data_size_y, const std::vector<unsigned char>& static_data){
00242 int m_ox, m_oy;
00243 worldToMapNoBounds(win_origin_x, win_origin_y, m_ox, m_oy);
00244
00245
00246 int bl_x = std::min(m_ox, 0);
00247 int bl_y = std::min(m_oy, 0);
00248 int ur_x = std::max(m_ox + data_size_x, size_x_);
00249 int ur_y = std::max(m_oy + data_size_y, size_y_);
00250
00251
00252 unsigned char* static_map_copy = new unsigned char[size_x_ * size_y_];
00253 memcpy(static_map_copy, static_map_, size_x_ * size_y_ * sizeof(unsigned char));
00254
00255
00256
00257 deleteMaps();
00258
00259
00260 double old_origin_x = origin_x_;
00261 double old_origin_y = origin_y_;
00262 unsigned int old_size_x = size_x_;
00263 unsigned int old_size_y = size_y_;
00264
00265 size_x_ = ur_x - bl_x;
00266 size_y_ = ur_y - bl_y;
00267 origin_x_ = std::min(origin_x_, win_origin_x);
00268 origin_y_ = std::min(origin_y_, win_origin_y);
00269
00270
00271 initMaps(size_x_, size_y_);
00272
00273
00274 resetMaps();
00275
00276
00277 unsigned int start_x, start_y;
00278 worldToMap(old_origin_x, old_origin_y, start_x, start_y);
00279 copyMapRegion(static_map_copy, 0, 0, old_size_x, costmap_, start_x, start_y, size_x_, old_size_x, old_size_y);
00280
00281 delete[] static_map_copy;
00282
00283
00284 replaceStaticMapWindow(win_origin_x, win_origin_y, data_size_x, data_size_y, static_data);
00285 }
00286
00287 void Costmap2D::updateStaticMapWindow(double win_origin_x, double win_origin_y,
00288 unsigned int data_size_x, unsigned int data_size_y,
00289 const std::vector<unsigned char>& static_data){
00290
00291 if(data_size_x * data_size_y != static_data.size()){
00292 ROS_ERROR("The sizes passed in are incorrect for the size of the static data char array. Doing nothing.");
00293 return;
00294 }
00295
00296
00297 int m_ox, m_oy;
00298 worldToMapNoBounds(win_origin_x, win_origin_y, m_ox, m_oy);
00299
00300
00301 if(m_ox <= 0 && m_oy <= 0 && (m_ox + data_size_x) >= size_x_ && (m_oy + data_size_y) >= size_y_){
00302 replaceFullMap(win_origin_x, win_origin_y, data_size_x, data_size_y, static_data);
00303 }
00304
00305 else if(m_ox < 0 || m_oy < 0 || (m_ox + data_size_x) > size_x_ || (m_oy + data_size_y) > size_y_){
00306 reshapeStaticMap(win_origin_x, win_origin_y, data_size_x, data_size_y, static_data);
00307 }
00308
00309 else{
00310 replaceStaticMapWindow(win_origin_x, win_origin_y, data_size_x, data_size_y, static_data);
00311 }
00312 }
00313
00314 void Costmap2D::deleteMaps(){
00315
00316 delete[] costmap_;
00317 delete[] static_map_;
00318 delete[] markers_;
00319 }
00320
00321 void Costmap2D::deleteKernels(){
00322 if(cached_distances_ != NULL){
00323 for(unsigned int i = 0; i <= cell_inflation_radius_ + 1; ++i){
00324 delete[] cached_distances_[i];
00325 }
00326 delete[] cached_distances_;
00327 }
00328
00329 if(cached_costs_ != NULL){
00330 for(unsigned int i = 0; i <= cell_inflation_radius_ + 1; ++i){
00331 delete[] cached_costs_[i];
00332 }
00333 delete[] cached_costs_;
00334 }
00335 }
00336
00337 void Costmap2D::initMaps(unsigned int size_x, unsigned int size_y){
00338 costmap_ = new unsigned char[size_x * size_y];
00339 static_map_ = new unsigned char[size_x * size_y];
00340 markers_ = new unsigned char[size_x * size_y];
00341
00342
00343 memset(markers_, 0, size_x_ * size_y_ * sizeof(unsigned char));
00344 }
00345
00346 void Costmap2D::resetMaps(){
00347
00348 if(track_unknown_space_){
00349 memset(static_map_, NO_INFORMATION, size_x_ * size_y_ * sizeof(unsigned char));
00350 memset(costmap_, NO_INFORMATION, size_x_ * size_y_ * sizeof(unsigned char));
00351 }
00352 else{
00353 memset(static_map_, FREE_SPACE, size_x_ * size_y_ * sizeof(unsigned char));
00354 memset(costmap_, FREE_SPACE, size_x_ * size_y_ * sizeof(unsigned char));
00355 }
00356 }
00357
00358 void Costmap2D::copyKernels(const Costmap2D& map, unsigned int cell_inflation_radius){
00359 cached_costs_ = new unsigned char*[cell_inflation_radius + 2];
00360 cached_distances_ = new double*[cell_inflation_radius + 2];
00361 for(unsigned int i = 0; i <= cell_inflation_radius + 1; ++i){
00362 cached_costs_[i] = new unsigned char[cell_inflation_radius + 2];
00363 cached_distances_[i] = new double[cell_inflation_radius + 2];
00364 for(unsigned int j = 0; j <= cell_inflation_radius + 1; ++j){
00365 cached_distances_[i][j] = map.cached_distances_[i][j];
00366 cached_costs_[i][j] = map.cached_costs_[i][j];
00367 }
00368 }
00369 }
00370
00371 void Costmap2D::copyCostmapWindow(const Costmap2D& map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y){
00372
00373 if(this == &map){
00374 ROS_ERROR("Cannot convert this costmap into a window of itself");
00375 return;
00376 }
00377
00378
00379 deleteMaps();
00380 deleteKernels();
00381
00382
00383 unsigned int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
00384 if(!map.worldToMap(win_origin_x, win_origin_y, lower_left_x, lower_left_y)
00385 || ! map.worldToMap(win_origin_x + win_size_x, win_origin_y + win_size_y, upper_right_x, upper_right_y)){
00386 ROS_ERROR("Cannot window a map that the window bounds don't fit inside of");
00387 return;
00388 }
00389
00390 size_x_ = upper_right_x - lower_left_x;
00391 size_y_ = upper_right_y - lower_left_y;
00392 resolution_ = map.resolution_;
00393 origin_x_ = win_origin_x;
00394 origin_y_ = win_origin_y;
00395
00396 ROS_DEBUG("ll(%d, %d), ur(%d, %d), size(%d, %d), origin(%.2f, %.2f)",
00397 lower_left_x, lower_left_y, upper_right_x, upper_right_y, size_x_, size_y_, origin_x_, origin_y_);
00398
00399
00400
00401 initMaps(size_x_, size_y_);
00402
00403
00404 copyMapRegion(map.costmap_, lower_left_x, lower_left_y, map.size_x_, costmap_, 0, 0, size_x_, size_x_, size_y_);
00405 copyMapRegion(map.static_map_, lower_left_x, lower_left_y, map.size_x_, static_map_, 0, 0, size_x_, size_x_, size_y_);
00406
00407 max_obstacle_range_ = map.max_obstacle_range_;
00408 max_obstacle_height_ = map.max_obstacle_height_;
00409 max_raytrace_range_ = map.max_raytrace_range_;
00410
00411 inscribed_radius_ = map.inscribed_radius_;
00412 circumscribed_radius_ = map.circumscribed_radius_;
00413 inflation_radius_ = map.inflation_radius_;
00414
00415 cell_inscribed_radius_ = map.cell_inscribed_radius_;
00416 cell_circumscribed_radius_ = map.cell_circumscribed_radius_;
00417 cell_inflation_radius_ = map.cell_inflation_radius_;
00418
00419
00420 circumscribed_cost_lb_ = map.circumscribed_cost_lb_;
00421
00422 weight_ = map.weight_;
00423
00424
00425 copyKernels(map, cell_inflation_radius_);
00426 }
00427
00428 Costmap2D& Costmap2D::operator=(const Costmap2D& map) {
00429
00430 if(this == &map)
00431 return *this;
00432
00433
00434 deleteMaps();
00435 deleteKernels();
00436
00437 size_x_ = map.size_x_;
00438 size_y_ = map.size_y_;
00439 resolution_ = map.resolution_;
00440 origin_x_ = map.origin_x_;
00441 origin_y_ = map.origin_y_;
00442
00443
00444 initMaps(size_x_, size_y_);
00445
00446
00447 memcpy(static_map_, map.static_map_, size_x_ * size_y_ * sizeof(unsigned char));
00448
00449
00450 memcpy(costmap_, map.costmap_, size_x_ * size_y_ * sizeof(unsigned char));
00451
00452 max_obstacle_range_ = map.max_obstacle_range_;
00453 max_obstacle_height_ = map.max_obstacle_height_;
00454 max_raytrace_range_ = map.max_raytrace_range_;
00455
00456 inscribed_radius_ = map.inscribed_radius_;
00457 circumscribed_radius_ = map.circumscribed_radius_;
00458 inflation_radius_ = map.inflation_radius_;
00459
00460 cell_inscribed_radius_ = map.cell_inscribed_radius_;
00461 cell_circumscribed_radius_ = map.cell_circumscribed_radius_;
00462 cell_inflation_radius_ = map.cell_inflation_radius_;
00463
00464
00465 circumscribed_cost_lb_ = map.circumscribed_cost_lb_;
00466
00467 weight_ = map.weight_;
00468
00469
00470 copyKernels(map, cell_inflation_radius_);
00471
00472 return *this;
00473 }
00474
00475 Costmap2D::Costmap2D(const Costmap2D& map) : static_map_(NULL), costmap_(NULL), markers_(NULL), cached_costs_(NULL), cached_distances_(NULL) {
00476 *this = map;
00477 }
00478
00479
00480 Costmap2D::Costmap2D() : size_x_(0), size_y_(0), resolution_(0.0), origin_x_(0.0), origin_y_(0.0), static_map_(NULL),
00481 costmap_(NULL), markers_(NULL), cached_costs_(NULL), cached_distances_(NULL) {}
00482
00483 Costmap2D::~Costmap2D(){
00484 deleteMaps();
00485 deleteKernels();
00486 }
00487
00488 unsigned int Costmap2D::cellDistance(double world_dist){
00489 double cells_dist = max(0.0, ceil(world_dist / resolution_));
00490 return (unsigned int) cells_dist;
00491 }
00492
00493 const unsigned char* Costmap2D::getCharMap() const {
00494 return costmap_;
00495 }
00496
00497 unsigned char Costmap2D::getCost(unsigned int mx, unsigned int my) const {
00498 ROS_ASSERT_MSG(mx < size_x_ && my < size_y_, "You cannot get the cost of a cell that is outside the bounds of the costmap");
00499 return costmap_[getIndex(mx, my)];
00500 }
00501
00502 void Costmap2D::setCost(unsigned int mx, unsigned int my, unsigned char cost) {
00503 ROS_ASSERT_MSG(mx < size_x_ && my < size_y_, "You cannot set the cost of a cell that is outside the bounds of the costmap");
00504 costmap_[getIndex(mx, my)] = cost;
00505 }
00506
00507 void Costmap2D::mapToWorld(unsigned int mx, unsigned int my, double& wx, double& wy) const {
00508 wx = origin_x_ + (mx + 0.5) * resolution_;
00509 wy = origin_y_ + (my + 0.5) * resolution_;
00510 }
00511
00512 bool Costmap2D::worldToMap(double wx, double wy, unsigned int& mx, unsigned int& my) const {
00513 if(wx < origin_x_ || wy < origin_y_)
00514 return false;
00515
00516 mx = (int) ((wx - origin_x_) / resolution_);
00517 my = (int) ((wy - origin_y_) / resolution_);
00518
00519 if(mx < size_x_ && my < size_y_)
00520 return true;
00521
00522 return false;
00523 }
00524
00525 void Costmap2D::worldToMapNoBounds(double wx, double wy, int& mx, int& my) const {
00526 mx = (int) ((wx - origin_x_) / resolution_);
00527 my = (int) ((wy - origin_y_) / resolution_);
00528 }
00529
00530 void Costmap2D::resetMapOutsideWindow(double wx, double wy, double w_size_x, double w_size_y){
00531 ROS_ASSERT_MSG(w_size_x >= 0 && w_size_y >= 0, "You cannot specify a negative size window");
00532
00533 double start_point_x = wx - w_size_x / 2;
00534 double start_point_y = wy - w_size_y / 2;
00535 double end_point_x = start_point_x + w_size_x;
00536 double end_point_y = start_point_y + w_size_y;
00537
00538
00539 start_point_x = max(origin_x_, start_point_x);
00540 start_point_y = max(origin_y_, start_point_y);
00541
00542
00543 end_point_x = min(origin_x_ + getSizeInMetersX(), end_point_x);
00544 end_point_y = min(origin_y_ + getSizeInMetersY(), end_point_y);
00545
00546 unsigned int start_x, start_y, end_x, end_y;
00547
00548
00549 if(!worldToMap(start_point_x, start_point_y, start_x, start_y) || !worldToMap(end_point_x, end_point_y, end_x, end_y))
00550 return;
00551
00552 ROS_ASSERT(end_x >= start_x && end_y >= start_y);
00553 unsigned int cell_size_x = end_x - start_x;
00554 unsigned int cell_size_y = end_y - start_y;
00555
00556
00557 unsigned char* local_map = new unsigned char[cell_size_x * cell_size_y];
00558
00559
00560 copyMapRegion(costmap_, start_x, start_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
00561
00562
00563 memcpy(costmap_, static_map_, size_x_ * size_y_ * sizeof(unsigned char));
00564
00565
00566 copyMapRegion(local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y);
00567
00568
00569 delete[] local_map;
00570 }
00571
00572 void Costmap2D::updateWorld(double robot_x, double robot_y,
00573 const vector<Observation>& observations, const vector<Observation>& clearing_observations){
00574
00575 memset(markers_, 0, size_x_ * size_y_ * sizeof(unsigned char));
00576
00577
00578 ROS_ASSERT_MSG(inflation_queue_.empty(), "The inflation queue must be empty at the beginning of inflation");
00579
00580
00581 raytraceFreespace(clearing_observations);
00582
00583
00584 double inflation_window_size = 2 * (max_raytrace_range_ + inflation_radius_);
00585
00586
00587 clearNonLethal(robot_x, robot_y, inflation_window_size, inflation_window_size);
00588
00589
00590 resetInflationWindow(robot_x, robot_y, inflation_window_size + 2 * inflation_radius_, inflation_window_size + 2 * inflation_radius_, inflation_queue_, false);
00591
00592
00593 updateObstacles(observations, inflation_queue_);
00594
00595 inflateObstacles(inflation_queue_);
00596 }
00597
00598 void Costmap2D::reinflateWindow(double wx, double wy, double w_size_x, double w_size_y, bool clear){
00599
00600 memset(markers_, 0, size_x_ * size_y_ * sizeof(unsigned char));
00601
00602
00603 ROS_ASSERT_MSG(inflation_queue_.empty(), "The inflation queue must be empty at the beginning of inflation");
00604
00605
00606 resetInflationWindow(wx, wy, w_size_x, w_size_y, inflation_queue_, clear);
00607
00608
00609 inflateObstacles(inflation_queue_);
00610
00611 }
00612
00613 void Costmap2D::updateObstacles(const vector<Observation>& observations, priority_queue<CellData>& inflation_queue){
00614
00615 for(vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it){
00616 const Observation& obs = *it;
00617
00618 const pcl::PointCloud<pcl::PointXYZ>& cloud =obs.cloud_;
00619
00620 double sq_obstacle_range = obs.obstacle_range_ * obs.obstacle_range_;
00621
00622
00623 for(unsigned int i = 0; i < cloud.points.size(); ++i){
00624
00625 if(cloud.points[i].z > max_obstacle_height_){
00626 ROS_DEBUG("The point is too high");
00627 continue;
00628 }
00629
00630
00631 double sq_dist = (cloud.points[i].x - obs.origin_.x) * (cloud.points[i].x - obs.origin_.x)
00632 + (cloud.points[i].y - obs.origin_.y) * (cloud.points[i].y - obs.origin_.y)
00633 + (cloud.points[i].z - obs.origin_.z) * (cloud.points[i].z - obs.origin_.z);
00634
00635
00636 if(sq_dist >= sq_obstacle_range){
00637 ROS_DEBUG("The point is too far away");
00638 continue;
00639 }
00640
00641
00642 unsigned int mx, my;
00643 if(!worldToMap(cloud.points[i].x, cloud.points[i].y, mx, my)){
00644 ROS_DEBUG("Computing map coords failed");
00645 continue;
00646 }
00647
00648 unsigned int index = getIndex(mx, my);
00649
00650
00651 enqueue(index, mx, my, mx, my, inflation_queue);
00652 }
00653 }
00654 }
00655
00656 void Costmap2D::inflateObstacles(priority_queue<CellData>& inflation_queue){
00657 while(!inflation_queue.empty()){
00658
00659 const CellData& current_cell = inflation_queue.top();
00660
00661 unsigned int index = current_cell.index_;
00662 unsigned int mx = current_cell.x_;
00663 unsigned int my = current_cell.y_;
00664 unsigned int sx = current_cell.src_x_;
00665 unsigned int sy = current_cell.src_y_;
00666
00667
00668 if(mx > 0)
00669 enqueue(index - 1, mx - 1, my, sx, sy, inflation_queue);
00670 if(my > 0)
00671 enqueue(index - size_x_, mx, my - 1, sx, sy, inflation_queue);
00672 if(mx < size_x_ - 1)
00673 enqueue(index + 1, mx + 1, my, sx, sy, inflation_queue);
00674 if(my < size_y_ - 1)
00675 enqueue(index + size_x_, mx, my + 1, sx, sy, inflation_queue);
00676
00677
00678 inflation_queue.pop();
00679 }
00680 }
00681
00682
00683 void Costmap2D::raytraceFreespace(const std::vector<Observation>& clearing_observations){
00684 for(unsigned int i = 0; i < clearing_observations.size(); ++i){
00685 raytraceFreespace(clearing_observations[i]);
00686 }
00687 }
00688
00689 void Costmap2D::raytraceFreespace(const Observation& clearing_observation){
00690
00691 ClearCell clearer(costmap_);
00692
00693 double ox = clearing_observation.origin_.x;
00694 double oy = clearing_observation.origin_.y;
00695 pcl::PointCloud<pcl::PointXYZ> cloud = clearing_observation.cloud_;
00696
00697
00698 unsigned int x0, y0;
00699 if(!worldToMap(ox, oy, x0, y0)){
00700 ROS_WARN("The origin for the sensor at (%.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.", ox, oy);
00701 return;
00702 }
00703
00704
00705 double map_end_x = origin_x_ + getSizeInMetersX();
00706 double map_end_y = origin_y_ + getSizeInMetersY();
00707
00708
00709 for(unsigned int i = 0; i < cloud.points.size(); ++i){
00710 double wx = cloud.points[i].x;
00711 double wy = cloud.points[i].y;
00712
00713
00714
00715 double a = wx - ox;
00716 double b = wy - oy;
00717
00718
00719 if(wx < origin_x_){
00720 double t = (origin_x_ - ox) / a;
00721 wx = origin_x_;
00722 wy = oy + b * t;
00723 }
00724 if(wy < origin_y_){
00725 double t = (origin_y_ - oy) / b;
00726 wx = ox + a * t;
00727 wy = origin_y_;
00728 }
00729
00730
00731 if(wx > map_end_x){
00732 double t = (map_end_x - ox) / a;
00733 wx = map_end_x;
00734 wy = oy + b * t;
00735 }
00736 if(wy > map_end_y){
00737 double t = (map_end_y - oy) / b;
00738 wx = ox + a * t;
00739 wy = map_end_y;
00740 }
00741
00742
00743 unsigned int x1, y1;
00744
00745
00746 if(!worldToMap(wx, wy, x1, y1))
00747 continue;
00748
00749 unsigned int cell_raytrace_range = cellDistance(clearing_observation.raytrace_range_);
00750
00751
00752 raytraceLine(clearer, x0, y0, x1, y1, cell_raytrace_range);
00753 }
00754 }
00755
00756 void Costmap2D::clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info){
00757
00758 unsigned int mx, my;
00759 if(!worldToMap(wx, wy, mx, my))
00760 return;
00761
00762
00763 double start_x = wx - w_size_x / 2;
00764 double start_y = wy - w_size_y / 2;
00765 double end_x = start_x + w_size_x;
00766 double end_y = start_y + w_size_y;
00767
00768
00769 start_x = max(origin_x_, start_x);
00770 start_y = max(origin_y_, start_y);
00771
00772 end_x = min(origin_x_ + getSizeInMetersX(), end_x);
00773 end_y = min(origin_y_ + getSizeInMetersY(), end_y);
00774
00775
00776 unsigned int map_sx, map_sy, map_ex, map_ey;
00777
00778
00779 if(!worldToMap(start_x, start_y, map_sx, map_sy) || !worldToMap(end_x, end_y, map_ex, map_ey))
00780 return;
00781
00782
00783 unsigned int index = getIndex(map_sx, map_sy);
00784 unsigned char* current = &costmap_[index];
00785 for(unsigned int j = map_sy; j <= map_ey; ++j){
00786 for(unsigned int i = map_sx; i <= map_ex; ++i){
00787
00788 if(*current != LETHAL_OBSTACLE){
00789 if(clear_no_info || *current != NO_INFORMATION)
00790 *current = FREE_SPACE;
00791 }
00792 current++;
00793 index++;
00794 }
00795 current += size_x_ - (map_ex - map_sx) - 1;
00796 index += size_x_ - (map_ex - map_sx) - 1;
00797 }
00798 }
00799
00800 void Costmap2D::resetInflationWindow(double wx, double wy, double w_size_x, double w_size_y,
00801 priority_queue<CellData>& inflation_queue, bool clear){
00802
00803 unsigned int mx, my;
00804 if(!worldToMap(wx, wy, mx, my))
00805 return;
00806
00807
00808 double start_x = wx - w_size_x / 2;
00809 double start_y = wy - w_size_y / 2;
00810 double end_x = start_x + w_size_x;
00811 double end_y = start_y + w_size_y;
00812
00813
00814 start_x = max(origin_x_, start_x);
00815 start_y = max(origin_y_, start_y);
00816
00817 end_x = min(origin_x_ + getSizeInMetersX(), end_x);
00818 end_y = min(origin_y_ + getSizeInMetersY(), end_y);
00819
00820
00821 unsigned int map_sx, map_sy, map_ex, map_ey;
00822
00823
00824 if(!worldToMap(start_x, start_y, map_sx, map_sy) || !worldToMap(end_x, end_y, map_ex, map_ey)){
00825 ROS_ERROR("Bounds not legal for reset window. Doing nothing.");
00826 return;
00827 }
00828
00829
00830 unsigned int index = getIndex(map_sx, map_sy);
00831 unsigned char* current = &costmap_[index];
00832 for(unsigned int j = map_sy; j <= map_ey; ++j){
00833 for(unsigned int i = map_sx; i <= map_ex; ++i){
00834
00835 if(*current == LETHAL_OBSTACLE)
00836 enqueue(index, i, j, i, j, inflation_queue);
00837 else if(clear && *current != NO_INFORMATION)
00838 *current = FREE_SPACE;
00839 current++;
00840 index++;
00841 }
00842 current += size_x_ - (map_ex - map_sx) - 1;
00843 index += size_x_ - (map_ex - map_sx) - 1;
00844 }
00845 }
00846
00847 void Costmap2D::updateOrigin(double new_origin_x, double new_origin_y){
00848
00849 int cell_ox, cell_oy;
00850 cell_ox = int((new_origin_x - origin_x_) / resolution_);
00851 cell_oy = int((new_origin_y - origin_y_) / resolution_);
00852
00853
00854
00855 double new_grid_ox, new_grid_oy;
00856 new_grid_ox = origin_x_ + cell_ox * resolution_;
00857 new_grid_oy = origin_y_ + cell_oy * resolution_;
00858
00859
00860 int size_x = size_x_;
00861 int size_y = size_y_;
00862
00863
00864 int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
00865 lower_left_x = min(max(cell_ox, 0), size_x);
00866 lower_left_y = min(max(cell_oy, 0), size_y);
00867 upper_right_x = min(max(cell_ox + size_x, 0), size_x);
00868 upper_right_y = min(max(cell_oy + size_y, 0), size_y);
00869
00870 unsigned int cell_size_x = upper_right_x - lower_left_x;
00871 unsigned int cell_size_y = upper_right_y - lower_left_y;
00872
00873
00874 unsigned char* local_map = new unsigned char[cell_size_x * cell_size_y];
00875
00876
00877 copyMapRegion(costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
00878
00879
00880 resetMaps();
00881
00882
00883 origin_x_ = new_grid_ox;
00884 origin_y_ = new_grid_oy;
00885
00886
00887 int start_x = lower_left_x - cell_ox;
00888 int start_y = lower_left_y - cell_oy;
00889
00890
00891 copyMapRegion(local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y);
00892
00893
00894 delete[] local_map;
00895
00896 }
00897
00898 bool Costmap2D::setConvexPolygonCost(const std::vector<geometry_msgs::Point>& polygon, unsigned char cost_value) {
00899
00900 std::vector<MapLocation> map_polygon;
00901 for(unsigned int i = 0; i < polygon.size(); ++i){
00902 MapLocation loc;
00903 if(!worldToMap(polygon[i].x, polygon[i].y, loc.x, loc.y)){
00904 ROS_DEBUG("Polygon lies outside map bounds, so we can't fill it");
00905 return false;
00906 }
00907 map_polygon.push_back(loc);
00908 }
00909
00910 std::vector<MapLocation> polygon_cells;
00911
00912
00913 convexFillCells(map_polygon, polygon_cells);
00914
00915
00916 for(unsigned int i = 0; i < polygon_cells.size(); ++i){
00917 unsigned int index = getIndex(polygon_cells[i].x, polygon_cells[i].y);
00918 costmap_[index] = cost_value;
00919 }
00920 return true;
00921 }
00922
00923 void Costmap2D::polygonOutlineCells(const std::vector<MapLocation>& polygon, std::vector<MapLocation>& polygon_cells){
00924 PolygonOutlineCells cell_gatherer(*this, costmap_, polygon_cells);
00925 for(unsigned int i = 0; i < polygon.size() - 1; ++i){
00926 raytraceLine(cell_gatherer, polygon[i].x, polygon[i].y, polygon[i + 1].x, polygon[i + 1].y);
00927 }
00928 if(!polygon.empty()){
00929 unsigned int last_index = polygon.size() - 1;
00930
00931 raytraceLine(cell_gatherer, polygon[last_index].x, polygon[last_index].y, polygon[0].x, polygon[0].y);
00932 }
00933 }
00934
00935 void Costmap2D::convexFillCells(const std::vector<MapLocation>& polygon, std::vector<MapLocation>& polygon_cells){
00936
00937 if(polygon.size() < 3)
00938 return;
00939
00940
00941 polygonOutlineCells(polygon, polygon_cells);
00942
00943
00944 MapLocation swap;
00945 unsigned int i = 0;
00946 while(i < polygon_cells.size() - 1){
00947 if(polygon_cells[i].x > polygon_cells[i + 1].x){
00948 swap = polygon_cells[i];
00949 polygon_cells[i] = polygon_cells[i + 1];
00950 polygon_cells[i + 1] = swap;
00951
00952 if(i > 0)
00953 --i;
00954 }
00955 else
00956 ++i;
00957 }
00958
00959 i = 0;
00960 MapLocation min_pt;
00961 MapLocation max_pt;
00962 unsigned int min_x = polygon_cells[0].x;
00963 unsigned int max_x = polygon_cells[polygon_cells.size() -1].x;
00964
00965
00966 for(unsigned int x = min_x; x <= max_x; ++x){
00967 if(i >= polygon_cells.size() - 1)
00968 break;
00969
00970 if(polygon_cells[i].y < polygon_cells[i + 1].y){
00971 min_pt = polygon_cells[i];
00972 max_pt = polygon_cells[i + 1];
00973 }
00974 else{
00975 min_pt = polygon_cells[i + 1];
00976 max_pt = polygon_cells[i];
00977 }
00978
00979 i += 2;
00980 while(i < polygon_cells.size() && polygon_cells[i].x == x){
00981 if(polygon_cells[i].y < min_pt.y)
00982 min_pt = polygon_cells[i];
00983 else if(polygon_cells[i].y > max_pt.y)
00984 max_pt = polygon_cells[i];
00985 ++i;
00986 }
00987
00988 MapLocation pt;
00989
00990 for(unsigned int y = min_pt.y; y < max_pt.y; ++y){
00991 pt.x = x;
00992 pt.y = y;
00993 polygon_cells.push_back(pt);
00994
00995 }
00996 }
00997 }
00998
00999 unsigned int Costmap2D::getSizeInCellsX() const{
01000 return size_x_;
01001 }
01002
01003 unsigned int Costmap2D::getSizeInCellsY() const{
01004 return size_y_;
01005 }
01006
01007 double Costmap2D::getSizeInMetersX() const{
01008 return (size_x_ - 1 + 0.5) * resolution_;
01009 }
01010
01011 double Costmap2D::getSizeInMetersY() const{
01012 return (size_y_ - 1 + 0.5) * resolution_;
01013 }
01014
01015 double Costmap2D::getOriginX() const{
01016 return origin_x_;
01017 }
01018
01019 double Costmap2D::getOriginY() const{
01020 return origin_y_;
01021 }
01022
01023 double Costmap2D::getResolution() const{
01024 return resolution_;
01025 }
01026
01027 bool Costmap2D::isCircumscribedCell(unsigned int x, unsigned int y) const {
01028 unsigned char cost = getCost(x, y);
01029 if(cost < INSCRIBED_INFLATED_OBSTACLE && cost >= circumscribed_cost_lb_)
01030 return true;
01031 return false;
01032 }
01033
01034 void Costmap2D::saveMap(std::string file_name){
01035 FILE *fp = fopen(file_name.c_str(), "w");
01036
01037 if(!fp){
01038 ROS_WARN("Can't open file %s", file_name.c_str());
01039 return;
01040 }
01041
01042 fprintf(fp, "P2\n%d\n%d\n%d\n", size_x_, size_y_, 0xff);
01043 for(unsigned int iy = 0; iy < size_y_; iy++) {
01044 for(unsigned int ix = 0; ix < size_x_; ix++) {
01045 unsigned char cost = getCost(ix,iy);
01046 if (cost == LETHAL_OBSTACLE) {
01047 fprintf(fp, "255 ");
01048 }
01049 else if (cost == NO_INFORMATION){
01050 fprintf(fp, "180 ");
01051 }
01052 else if (cost == INSCRIBED_INFLATED_OBSTACLE ) {
01053 fprintf(fp, "128 ");
01054 }
01055 else if (cost > 0){
01056 fprintf(fp, "50 ");
01057 }
01058 else {
01059 fprintf(fp, "0 ");
01060 }
01061 }
01062 fprintf(fp, "\n");
01063 }
01064 fclose(fp);
01065 }
01066
01067 };