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