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/voxel_costmap_2d.h>
00038
00039 #define VOXEL_BITS 16
00040
00041 using namespace std;
00042
00043 namespace costmap_2d{
00044 VoxelCostmap2D::VoxelCostmap2D(unsigned int cells_size_x, unsigned int cells_size_y, unsigned int cells_size_z,
00045 double xy_resolution, double z_resolution, double origin_x, double origin_y, double origin_z, double inscribed_radius,
00046 double circumscribed_radius, double inflation_radius, double obstacle_range,
00047 double raytrace_range, double weight,
00048 const std::vector<unsigned char>& static_data, unsigned char lethal_threshold, unsigned int unknown_threshold, unsigned int mark_threshold, unsigned char unknown_cost_value)
00049 : Costmap2D(cells_size_x, cells_size_y, xy_resolution, origin_x, origin_y, inscribed_radius, circumscribed_radius,
00050 inflation_radius, obstacle_range, cells_size_z * z_resolution + origin_z, raytrace_range, weight, static_data, lethal_threshold, unknown_threshold < cells_size_z, unknown_cost_value),
00051 voxel_grid_(cells_size_x, cells_size_y, cells_size_z), xy_resolution_(xy_resolution), z_resolution_(z_resolution),
00052 origin_z_(origin_z), unknown_threshold_(unknown_threshold + (VOXEL_BITS - cells_size_z)), mark_threshold_(mark_threshold), size_z_(cells_size_z)
00053 {
00054 }
00055
00056 VoxelCostmap2D::~VoxelCostmap2D(){}
00057
00058 void VoxelCostmap2D::initMaps(unsigned int size_x, unsigned int size_y){
00059 Costmap2D::initMaps(size_x, size_y);
00060 voxel_grid_.resize(size_x, size_y, size_z_);
00061 ROS_ASSERT(voxel_grid_.sizeX() == size_x_ && voxel_grid_.sizeY() == size_y_);
00062 }
00063
00064 void VoxelCostmap2D::resetMaps(){
00065 Costmap2D::resetMaps();
00066 voxel_grid_.reset();
00067 }
00068
00069 void VoxelCostmap2D::resetMapOutsideWindow(double wx, double wy, double w_size_x, double w_size_y){
00070 ROS_ASSERT_MSG(w_size_x >= 0 && w_size_y >= 0, "You cannot specify a negative size window");
00071
00072 double start_point_x = wx - w_size_x / 2;
00073 double start_point_y = wy - w_size_y / 2;
00074 double end_point_x = start_point_x + w_size_x;
00075 double end_point_y = start_point_y + w_size_y;
00076
00077
00078 start_point_x = max(origin_x_, start_point_x);
00079 start_point_y = max(origin_y_, start_point_y);
00080
00081
00082 end_point_x = min(origin_x_ + getSizeInMetersX(), end_point_x);
00083 end_point_y = min(origin_y_ + getSizeInMetersY(), end_point_y);
00084
00085 unsigned int start_x, start_y, end_x, end_y;
00086
00087
00088 if(!worldToMap(start_point_x, start_point_y, start_x, start_y) || !worldToMap(end_point_x, end_point_y, end_x, end_y))
00089 return;
00090
00091 ROS_ASSERT(end_x > start_x && end_y > start_y);
00092 unsigned int cell_size_x = end_x - start_x;
00093 unsigned int cell_size_y = end_y - start_y;
00094
00095
00096 unsigned char* local_map = new unsigned char[cell_size_x * cell_size_y];
00097 unsigned int* local_voxel_map = new unsigned int[cell_size_x * cell_size_y];
00098 unsigned int* voxel_map = voxel_grid_.getData();
00099
00100
00101 copyMapRegion(costmap_, start_x, start_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
00102 copyMapRegion(voxel_map, start_x, start_y, size_x_, local_voxel_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
00103
00104
00105 memcpy(costmap_, static_map_, size_x_ * size_y_ * sizeof(unsigned char));
00106
00107
00108 voxel_grid_.reset();
00109
00110
00111 copyMapRegion(local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y);
00112 copyMapRegion(local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_, cell_size_x, cell_size_y);
00113
00114
00115 delete[] local_map;
00116 delete[] local_voxel_map;
00117 }
00118
00119 void VoxelCostmap2D::updateObstacles(const vector<Observation>& observations, priority_queue<CellData>& inflation_queue){
00120
00121 for(vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it){
00122 const Observation& obs = *it;
00123
00124 const pcl::PointCloud<pcl::PointXYZ>& cloud =obs.cloud_;
00125
00126 double sq_obstacle_range = obs.obstacle_range_ * obs.obstacle_range_;
00127
00128 for(unsigned int i = 0; i < cloud.points.size(); ++i){
00129
00130 if(cloud.points[i].z > max_obstacle_height_)
00131 continue;
00132
00133
00134 double sq_dist = (cloud.points[i].x - obs.origin_.x) * (cloud.points[i].x - obs.origin_.x)
00135 + (cloud.points[i].y - obs.origin_.y) * (cloud.points[i].y - obs.origin_.y)
00136 + (cloud.points[i].z - obs.origin_.z) * (cloud.points[i].z - obs.origin_.z);
00137
00138
00139 if(sq_dist >= sq_obstacle_range)
00140 continue;
00141
00142
00143 unsigned int mx, my, mz;
00144 if(cloud.points[i].z < origin_z_){
00145 if(!worldToMap3D(cloud.points[i].x, cloud.points[i].y, origin_z_, mx, my, mz))
00146 continue;
00147 }
00148 else if(!worldToMap3D(cloud.points[i].x, cloud.points[i].y, cloud.points[i].z, mx, my, mz)){
00149 continue;
00150 }
00151
00152
00153 if(voxel_grid_.markVoxelInMap(mx, my, mz, mark_threshold_)){
00154 unsigned int index = getIndex(mx, my);
00155
00156
00157 enqueue(index, mx, my, mx, my, inflation_queue);
00158 }
00159 }
00160 }
00161 }
00162
00163 void VoxelCostmap2D::raytraceFreespace(const Observation& clearing_observation){
00164 if(clearing_observation.cloud_.points.size() == 0)
00165 return;
00166
00167
00168 double sensor_x, sensor_y, sensor_z;
00169 double ox = clearing_observation.origin_.x;
00170 double oy = clearing_observation.origin_.y;
00171 double oz = clearing_observation.origin_.z;
00172
00173 if(!worldToMap3DFloat(ox, oy, oz, sensor_x, sensor_y, sensor_z)){
00174 ROS_WARN("The origin for the sensor at (%.2f, %.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.", ox, oy, oz);
00175 return;
00176 }
00177
00178
00179 double map_end_x = origin_x_ + getSizeInMetersX();
00180 double map_end_y = origin_y_ + getSizeInMetersY();
00181
00182 for(unsigned int i = 0; i < clearing_observation.cloud_.points.size(); ++i){
00183 double wpx = clearing_observation.cloud_.points[i].x;
00184 double wpy = clearing_observation.cloud_.points[i].y;
00185 double wpz = clearing_observation.cloud_.points[i].z;
00186
00187 double distance = dist(ox, oy, oz, wpx, wpy, wpz);
00188 double scaling_fact = 1.0;
00189 scaling_fact = std::max(std::min(scaling_fact, (distance - 2 * xy_resolution_) / distance), 0.0);
00190 wpx = scaling_fact * (wpx - ox) + ox;
00191 wpy = scaling_fact * (wpy - oy) + oy;
00192 wpz = scaling_fact * (wpz - oz) + oz;
00193
00194 double a = wpx - ox;
00195 double b = wpy - oy;
00196 double c = wpz - oz;
00197 double t = 1.0;
00198
00199
00200 if(wpz > max_obstacle_height_){
00201
00202 t = std::min(t, (max_obstacle_height_ - 0.01 - oz) / c);
00203 }
00204
00205 else if(wpz < origin_z_){
00206
00207 t = std::min(t, (origin_z_ - oz) / c);
00208 }
00209
00210
00211 if(wpx < origin_x_){
00212 t = std::min(t, (origin_x_ - ox) / a);
00213 }
00214 if(wpy < origin_y_){
00215 t = std::min(t, (origin_y_ - oy) / b);
00216 }
00217
00218
00219 if(wpx > map_end_x){
00220 t = std::min(t, (map_end_x - ox) / a);
00221 }
00222 if(wpy > map_end_y){
00223 t = std::min(t, (map_end_y - oy) / b);
00224 }
00225
00226 wpx = ox + a * t;
00227 wpy = oy + b * t;
00228 wpz = oz + c * t;
00229
00230 double point_x, point_y, point_z;
00231 if(worldToMap3DFloat(wpx, wpy, wpz, point_x, point_y, point_z)){
00232 unsigned int cell_raytrace_range = cellDistance(clearing_observation.raytrace_range_);
00233
00234
00235 voxel_grid_.clearVoxelLineInMap(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z, costmap_,
00236 unknown_threshold_, mark_threshold_, FREE_SPACE, NO_INFORMATION, cell_raytrace_range);
00237 }
00238 }
00239 }
00240
00241
00242 void VoxelCostmap2D::updateOrigin(double new_origin_x, double new_origin_y){
00243
00244 int cell_ox, cell_oy;
00245 cell_ox = int((new_origin_x - origin_x_) / resolution_);
00246 cell_oy = int((new_origin_y - origin_y_) / resolution_);
00247
00248
00249
00250 double new_grid_ox, new_grid_oy;
00251 new_grid_ox = origin_x_ + cell_ox * resolution_;
00252 new_grid_oy = origin_y_ + cell_oy * resolution_;
00253
00254
00255 int size_x = size_x_;
00256 int size_y = size_y_;
00257
00258
00259 int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
00260 lower_left_x = min(max(cell_ox, 0), size_x);
00261 lower_left_y = min(max(cell_oy, 0), size_y);
00262 upper_right_x = min(max(cell_ox + size_x, 0), size_x);
00263 upper_right_y = min(max(cell_oy + size_y, 0), size_y);
00264
00265 unsigned int cell_size_x = upper_right_x - lower_left_x;
00266 unsigned int cell_size_y = upper_right_y - lower_left_y;
00267
00268
00269 unsigned char* local_map = new unsigned char[cell_size_x * cell_size_y];
00270 unsigned int* local_voxel_map = new unsigned int[cell_size_x * cell_size_y];
00271 unsigned int* voxel_map = voxel_grid_.getData();
00272
00273
00274 copyMapRegion(costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
00275 copyMapRegion(voxel_map, lower_left_x, lower_left_y, size_x_, local_voxel_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
00276
00277
00278 resetMaps();
00279
00280
00281 origin_x_ = new_grid_ox;
00282 origin_y_ = new_grid_oy;
00283
00284
00285 int start_x = lower_left_x - cell_ox;
00286 int start_y = lower_left_y - cell_oy;
00287
00288
00289 copyMapRegion(local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y);
00290 copyMapRegion(local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_, cell_size_x, cell_size_y);
00291
00292
00293 delete[] local_map;
00294 delete[] local_voxel_map;
00295
00296 }
00297
00298 void VoxelCostmap2D::clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info){
00299
00300 unsigned int mx, my;
00301 if(!worldToMap(wx, wy, mx, my))
00302 return;
00303
00304
00305 double start_x = wx - w_size_x / 2;
00306 double start_y = wy - w_size_y / 2;
00307 double end_x = start_x + w_size_x;
00308 double end_y = start_y + w_size_y;
00309
00310
00311 start_x = max(origin_x_, start_x);
00312 start_y = max(origin_y_, start_y);
00313
00314 end_x = min(origin_x_ + getSizeInMetersX(), end_x);
00315 end_y = min(origin_y_ + getSizeInMetersY(), end_y);
00316
00317
00318 unsigned int map_sx, map_sy, map_ex, map_ey;
00319
00320
00321 if(!worldToMap(start_x, start_y, map_sx, map_sy) || !worldToMap(end_x, end_y, map_ex, map_ey))
00322 return;
00323
00324
00325 unsigned int index = getIndex(map_sx, map_sy);
00326 unsigned char* current = &costmap_[index];
00327 for(unsigned int j = map_sy; j <= map_ey; ++j){
00328 for(unsigned int i = map_sx; i <= map_ex; ++i){
00329
00330 if(*current != LETHAL_OBSTACLE){
00331 if(clear_no_info || *current != NO_INFORMATION){
00332 *current = FREE_SPACE;
00333 voxel_grid_.clearVoxelColumn(index);
00334 }
00335 }
00336 current++;
00337 index++;
00338 }
00339 current += size_x_ - (map_ex - map_sx) - 1;
00340 index += size_x_ - (map_ex - map_sx) - 1;
00341 }
00342 }
00343
00344 void VoxelCostmap2D::getVoxelGridMessage(VoxelGrid& grid){
00345 unsigned int size = voxel_grid_.sizeX() * voxel_grid_.sizeY();
00346 grid.size_x = voxel_grid_.sizeX();
00347 grid.size_y = voxel_grid_.sizeY();
00348 grid.size_z = voxel_grid_.sizeZ();
00349 grid.data.resize(size);
00350 memcpy(&grid.data[0], voxel_grid_.getData(), size * sizeof(unsigned int));
00351
00352 grid.origin.x = origin_x_;
00353 grid.origin.y = origin_y_;
00354 grid.origin.z = origin_z_;
00355
00356 grid.resolutions.x = xy_resolution_;
00357 grid.resolutions.y = xy_resolution_;
00358 grid.resolutions.z = z_resolution_;
00359 }
00360
00361 void VoxelCostmap2D::getPoints(pcl::PointCloud<pcl::PointXYZ>& cloud){
00362 for(unsigned int i = 0; i < voxel_grid_.sizeX(); ++i){
00363 for(unsigned int j = 0; j < voxel_grid_.sizeY(); ++j){
00364 for(unsigned int k = 0; k < voxel_grid_.sizeZ(); ++k){
00365 if(voxel_grid_.getVoxel(i, j, k) == voxel_grid::MARKED){
00366 double wx, wy, wz;
00367 mapToWorld3D(i, j, k, wx, wy, wz);
00368 pcl::PointXYZ pt;
00369 pt.x = wx;
00370 pt.y = wy;
00371 pt.z = wz;
00372 cloud.points.push_back(pt);
00373 }
00374 }
00375 }
00376 }
00377 }
00378
00379
00380 };