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
00038 #include <costmap_2d/voxel_layer.h>
00039 #include <pluginlib/class_list_macros.h>
00040 #include <pcl_conversions/pcl_conversions.h>
00041
00042 #define VOXEL_BITS 16
00043 PLUGINLIB_EXPORT_CLASS(costmap_2d::VoxelLayer, costmap_2d::Layer)
00044
00045 using costmap_2d::NO_INFORMATION;
00046 using costmap_2d::LETHAL_OBSTACLE;
00047 using costmap_2d::FREE_SPACE;
00048
00049 using costmap_2d::ObservationBuffer;
00050 using costmap_2d::Observation;
00051
00052 namespace costmap_2d
00053 {
00054
00055 void VoxelLayer::onInitialize()
00056 {
00057 ObstacleLayer::onInitialize();
00058 ros::NodeHandle private_nh("~/" + name_);
00059
00060 private_nh.param("publish_voxel_map", publish_voxel_, false);
00061 if (publish_voxel_)
00062 voxel_pub_ = private_nh.advertise < costmap_2d::VoxelGrid > ("voxel_grid", 1);
00063
00064 clearing_endpoints_pub_ = private_nh.advertise<sensor_msgs::PointCloud>( "clearing_endpoints", 1 );
00065 }
00066
00067 void VoxelLayer::setupDynamicReconfigure(ros::NodeHandle& nh)
00068 {
00069 dsrv_ = new dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>(nh);
00070 dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>::CallbackType cb = boost::bind(
00071 &VoxelLayer::reconfigureCB, this, _1, _2);
00072 dsrv_->setCallback(cb);
00073 }
00074
00075 VoxelLayer::~VoxelLayer()
00076 {
00077 if(dsrv_)
00078 delete dsrv_;
00079 }
00080
00081 void VoxelLayer::reconfigureCB(costmap_2d::VoxelPluginConfig &config, uint32_t level)
00082 {
00083 enabled_ = config.enabled;
00084 max_obstacle_height_ = config.max_obstacle_height;
00085 size_z_ = config.z_voxels;
00086 origin_z_ = config.origin_z;
00087 z_resolution_ = config.z_resolution;
00088 unknown_threshold_ = config.unknown_threshold + (VOXEL_BITS - size_z_);
00089 mark_threshold_ = config.mark_threshold;
00090 combination_method_ = config.combination_method;
00091 matchSize();
00092 }
00093
00094 void VoxelLayer::matchSize()
00095 {
00096 ObstacleLayer::matchSize();
00097 voxel_grid_.resize(size_x_, size_y_, size_z_);
00098 ROS_ASSERT(voxel_grid_.sizeX() == size_x_ && voxel_grid_.sizeY() == size_y_);
00099 }
00100
00101 void VoxelLayer::reset()
00102 {
00103 deactivate();
00104 resetMaps();
00105 voxel_grid_.reset();
00106 activate();
00107 }
00108
00109 void VoxelLayer::resetMaps()
00110 {
00111 Costmap2D::resetMaps();
00112 voxel_grid_.reset();
00113 }
00114
00115 void VoxelLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x,
00116 double* min_y, double* max_x, double* max_y)
00117 {
00118 if (rolling_window_)
00119 updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
00120 if (!enabled_)
00121 return;
00122 useExtraBounds(min_x, min_y, max_x, max_y);
00123
00124 bool current = true;
00125 std::vector<Observation> observations, clearing_observations;
00126
00127
00128 current = current && getMarkingObservations(observations);
00129
00130
00131 current = current && getClearingObservations(clearing_observations);
00132
00133
00134 current_ = current;
00135
00136
00137 for (unsigned int i = 0; i < clearing_observations.size(); ++i)
00138 {
00139 raytraceFreespace(clearing_observations[i], min_x, min_y, max_x, max_y);
00140 }
00141
00142
00143 for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
00144 {
00145 const Observation& obs = *it;
00146
00147 const pcl::PointCloud<pcl::PointXYZ>& cloud = *(obs.cloud_);
00148
00149 double sq_obstacle_range = obs.obstacle_range_ * obs.obstacle_range_;
00150
00151 for (unsigned int i = 0; i < cloud.points.size(); ++i)
00152 {
00153
00154 if (cloud.points[i].z > max_obstacle_height_)
00155 continue;
00156
00157
00158 double sq_dist = (cloud.points[i].x - obs.origin_.x) * (cloud.points[i].x - obs.origin_.x)
00159 + (cloud.points[i].y - obs.origin_.y) * (cloud.points[i].y - obs.origin_.y)
00160 + (cloud.points[i].z - obs.origin_.z) * (cloud.points[i].z - obs.origin_.z);
00161
00162
00163 if (sq_dist >= sq_obstacle_range)
00164 continue;
00165
00166
00167 unsigned int mx, my, mz;
00168 if (cloud.points[i].z < origin_z_)
00169 {
00170 if (!worldToMap3D(cloud.points[i].x, cloud.points[i].y, origin_z_, mx, my, mz))
00171 continue;
00172 }
00173 else if (!worldToMap3D(cloud.points[i].x, cloud.points[i].y, cloud.points[i].z, mx, my, mz))
00174 {
00175 continue;
00176 }
00177
00178
00179 if (voxel_grid_.markVoxelInMap(mx, my, mz, mark_threshold_))
00180 {
00181 unsigned int index = getIndex(mx, my);
00182
00183 costmap_[index] = LETHAL_OBSTACLE;
00184 touch((double)cloud.points[i].x, (double)cloud.points[i].y, min_x, min_y, max_x, max_y);
00185 }
00186 }
00187 }
00188
00189 if (publish_voxel_)
00190 {
00191 costmap_2d::VoxelGrid grid_msg;
00192 unsigned int size = voxel_grid_.sizeX() * voxel_grid_.sizeY();
00193 grid_msg.size_x = voxel_grid_.sizeX();
00194 grid_msg.size_y = voxel_grid_.sizeY();
00195 grid_msg.size_z = voxel_grid_.sizeZ();
00196 grid_msg.data.resize(size);
00197 memcpy(&grid_msg.data[0], voxel_grid_.getData(), size * sizeof(unsigned int));
00198
00199 grid_msg.origin.x = origin_x_;
00200 grid_msg.origin.y = origin_y_;
00201 grid_msg.origin.z = origin_z_;
00202
00203 grid_msg.resolutions.x = resolution_;
00204 grid_msg.resolutions.y = resolution_;
00205 grid_msg.resolutions.z = z_resolution_;
00206 grid_msg.header.frame_id = global_frame_;
00207 grid_msg.header.stamp = ros::Time::now();
00208 voxel_pub_.publish(grid_msg);
00209 }
00210
00211 footprint_layer_.updateBounds(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
00212 }
00213
00214 void VoxelLayer::clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info)
00215 {
00216
00217 unsigned int mx, my;
00218 if (!worldToMap(wx, wy, mx, my))
00219 return;
00220
00221
00222 double start_x = wx - w_size_x / 2;
00223 double start_y = wy - w_size_y / 2;
00224 double end_x = start_x + w_size_x;
00225 double end_y = start_y + w_size_y;
00226
00227
00228 start_x = std::max(origin_x_, start_x);
00229 start_y = std::max(origin_y_, start_y);
00230
00231 end_x = std::min(origin_x_ + getSizeInMetersX(), end_x);
00232 end_y = std::min(origin_y_ + getSizeInMetersY(), end_y);
00233
00234
00235 unsigned int map_sx, map_sy, map_ex, map_ey;
00236
00237
00238 if (!worldToMap(start_x, start_y, map_sx, map_sy) || !worldToMap(end_x, end_y, map_ex, map_ey))
00239 return;
00240
00241
00242 unsigned int index = getIndex(map_sx, map_sy);
00243 unsigned char* current = &costmap_[index];
00244 for (unsigned int j = map_sy; j <= map_ey; ++j)
00245 {
00246 for (unsigned int i = map_sx; i <= map_ex; ++i)
00247 {
00248
00249 if (*current != LETHAL_OBSTACLE)
00250 {
00251 if (clear_no_info || *current != NO_INFORMATION)
00252 {
00253 *current = FREE_SPACE;
00254 voxel_grid_.clearVoxelColumn(index);
00255 }
00256 }
00257 current++;
00258 index++;
00259 }
00260 current += size_x_ - (map_ex - map_sx) - 1;
00261 index += size_x_ - (map_ex - map_sx) - 1;
00262 }
00263 }
00264
00265 void VoxelLayer::raytraceFreespace(const Observation& clearing_observation, double* min_x, double* min_y,
00266 double* max_x, double* max_y)
00267 {
00268 if (clearing_observation.cloud_->points.size() == 0)
00269 return;
00270
00271 double sensor_x, sensor_y, sensor_z;
00272 double ox = clearing_observation.origin_.x;
00273 double oy = clearing_observation.origin_.y;
00274 double oz = clearing_observation.origin_.z;
00275
00276 if (!worldToMap3DFloat(ox, oy, oz, sensor_x, sensor_y, sensor_z))
00277 {
00278 ROS_WARN_THROTTLE(
00279 1.0,
00280 "The origin for the sensor at (%.2f, %.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
00281 ox, oy, oz);
00282 return;
00283 }
00284
00285 bool publish_clearing_points = (clearing_endpoints_pub_.getNumSubscribers() > 0);
00286 if( publish_clearing_points )
00287 {
00288 clearing_endpoints_.points.clear();
00289 clearing_endpoints_.points.reserve( clearing_observation.cloud_->points.size() );
00290 }
00291
00292
00293 double map_end_x = origin_x_ + getSizeInMetersX();
00294 double map_end_y = origin_y_ + getSizeInMetersY();
00295
00296 for (unsigned int i = 0; i < clearing_observation.cloud_->points.size(); ++i)
00297 {
00298 double wpx = clearing_observation.cloud_->points[i].x;
00299 double wpy = clearing_observation.cloud_->points[i].y;
00300 double wpz = clearing_observation.cloud_->points[i].z;
00301
00302 double distance = dist(ox, oy, oz, wpx, wpy, wpz);
00303 double scaling_fact = 1.0;
00304 scaling_fact = std::max(std::min(scaling_fact, (distance - 2 * resolution_) / distance), 0.0);
00305 wpx = scaling_fact * (wpx - ox) + ox;
00306 wpy = scaling_fact * (wpy - oy) + oy;
00307 wpz = scaling_fact * (wpz - oz) + oz;
00308
00309 double a = wpx - ox;
00310 double b = wpy - oy;
00311 double c = wpz - oz;
00312 double t = 1.0;
00313
00314
00315 if (wpz > max_obstacle_height_)
00316 {
00317
00318 t = std::max(0.0, std::min(t, (max_obstacle_height_ - 0.01 - oz) / c));
00319 }
00320
00321 else if (wpz < origin_z_)
00322 {
00323
00324 t = std::min(t, (origin_z_ - oz) / c);
00325 }
00326
00327
00328 if (wpx < origin_x_)
00329 {
00330 t = std::min(t, (origin_x_ - ox) / a);
00331 }
00332 if (wpy < origin_y_)
00333 {
00334 t = std::min(t, (origin_y_ - oy) / b);
00335 }
00336
00337
00338 if (wpx > map_end_x)
00339 {
00340 t = std::min(t, (map_end_x - ox) / a);
00341 }
00342 if (wpy > map_end_y)
00343 {
00344 t = std::min(t, (map_end_y - oy) / b);
00345 }
00346
00347 wpx = ox + a * t;
00348 wpy = oy + b * t;
00349 wpz = oz + c * t;
00350
00351 double point_x, point_y, point_z;
00352 if (worldToMap3DFloat(wpx, wpy, wpz, point_x, point_y, point_z))
00353 {
00354 unsigned int cell_raytrace_range = cellDistance(clearing_observation.raytrace_range_);
00355
00356
00357 voxel_grid_.clearVoxelLineInMap(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z, costmap_,
00358 unknown_threshold_, mark_threshold_, FREE_SPACE, NO_INFORMATION,
00359 cell_raytrace_range);
00360
00361 updateRaytraceBounds(ox, oy, wpx, wpy, clearing_observation.raytrace_range_, min_x, min_y, max_x, max_y);
00362
00363 if( publish_clearing_points )
00364 {
00365 geometry_msgs::Point32 point;
00366 point.x = wpx;
00367 point.y = wpy;
00368 point.z = wpz;
00369 clearing_endpoints_.points.push_back( point );
00370 }
00371 }
00372 }
00373
00374 if( publish_clearing_points )
00375 {
00376 clearing_endpoints_.header.frame_id = global_frame_;
00377 clearing_endpoints_.header.stamp = pcl_conversions::fromPCL(clearing_observation.cloud_->header).stamp;
00378 clearing_endpoints_.header.seq = clearing_observation.cloud_->header.seq;
00379
00380 clearing_endpoints_pub_.publish( clearing_endpoints_ );
00381 }
00382 }
00383
00384 void VoxelLayer::updateOrigin(double new_origin_x, double new_origin_y)
00385 {
00386
00387 int cell_ox, cell_oy;
00388 cell_ox = int((new_origin_x - origin_x_) / resolution_);
00389 cell_oy = int((new_origin_y - origin_y_) / resolution_);
00390
00391
00392
00393 double new_grid_ox, new_grid_oy;
00394 new_grid_ox = origin_x_ + cell_ox * resolution_;
00395 new_grid_oy = origin_y_ + cell_oy * resolution_;
00396
00397
00398 int size_x = size_x_;
00399 int size_y = size_y_;
00400
00401
00402 int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
00403 lower_left_x = std::min(std::max(cell_ox, 0), size_x);
00404 lower_left_y = std::min(std::max(cell_oy, 0), size_y);
00405 upper_right_x = std::min(std::max(cell_ox + size_x, 0), size_x);
00406 upper_right_y = std::min(std::max(cell_oy + size_y, 0), size_y);
00407
00408 unsigned int cell_size_x = upper_right_x - lower_left_x;
00409 unsigned int cell_size_y = upper_right_y - lower_left_y;
00410
00411
00412 unsigned char* local_map = new unsigned char[cell_size_x * cell_size_y];
00413 unsigned int* local_voxel_map = new unsigned int[cell_size_x * cell_size_y];
00414 unsigned int* voxel_map = voxel_grid_.getData();
00415
00416
00417 copyMapRegion(costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
00418 copyMapRegion(voxel_map, lower_left_x, lower_left_y, size_x_, local_voxel_map, 0, 0, cell_size_x, cell_size_x,
00419 cell_size_y);
00420
00421
00422 resetMaps();
00423
00424
00425 origin_x_ = new_grid_ox;
00426 origin_y_ = new_grid_oy;
00427
00428
00429 int start_x = lower_left_x - cell_ox;
00430 int start_y = lower_left_y - cell_oy;
00431
00432
00433 copyMapRegion(local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y);
00434 copyMapRegion(local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_, cell_size_x, cell_size_y);
00435
00436
00437 delete[] local_map;
00438 delete[] local_voxel_map;
00439 }
00440
00441 }