41 #include <boost/thread.hpp>
60 ObstacleLayer::onInitialize();
63 std::string costmap_name =
name_.substr(0,
name_.find(
"/"));
78 voxel_dsrv_ =
new dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>(nh);
79 dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>::CallbackType cb = boost::bind(
106 ObstacleLayer::matchSize();
121 Costmap2D::resetMaps();
126 double* min_y,
double* max_x,
double* max_y)
135 std::vector<Observation> observations, clearing_observations;
147 for (
unsigned int i = 0; i < clearing_observations.size(); ++i)
153 for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
157 #ifdef COSTMAP_2D_POINTCLOUD2
158 const sensor_msgs::PointCloud2& cloud = *(obs.
cloud_);
165 for (
unsigned int i = 0; iter_x != iter_x.
end(); ++iter_x, ++iter_y, ++iter_z) {
166 const double x = *iter_x;
167 const double y = *iter_y;
168 const double z = *iter_z;
170 pcl::PointCloud<pcl::PointXYZ>::const_iterator point_it = obs.
cloud_->begin();
171 for (;point_it < obs.
cloud_->end(); ++point_it) {
172 const double x = point_it->x;
173 const double y = point_it->y;
174 const double z = point_it->z;
177 unsigned int mx, my, mz;
184 unsigned int index =
getIndex(mx, my);
187 touch(x, y, min_x, min_y, max_x, max_y);
194 costmap_2d::VoxelGrid grid_msg;
199 grid_msg.data.resize(size);
214 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
225 double start_x = wx - w_size_x / 2;
226 double start_y = wy - w_size_y / 2;
227 double end_x = start_x + w_size_x;
228 double end_y = start_y + w_size_y;
238 unsigned int map_sx, map_sy, map_ex, map_ey;
245 unsigned int index =
getIndex(map_sx, map_sy);
246 unsigned char* current = &
costmap_[index];
247 for (
unsigned int j = map_sy; j <= map_ey; ++j)
249 for (
unsigned int i = map_sx; i <= map_ex; ++i)
252 if (*current != LETHAL_OBSTACLE)
254 if (clear_no_info || *current != NO_INFORMATION)
256 *current = FREE_SPACE;
263 current +=
size_x_ - (map_ex - map_sx) - 1;
264 index +=
size_x_ - (map_ex - map_sx) - 1;
269 double* max_x,
double* max_y)
271 size_t clearing_observation_cloud_size = clearing_observation.
cloud_->height * clearing_observation.
cloud_->width;
272 if (clearing_observation_cloud_size == 0)
275 double sensor_x, sensor_y, sensor_z;
276 double ox = clearing_observation.
origin_.x;
277 double oy = clearing_observation.
origin_.y;
278 double oz = clearing_observation.
origin_.z;
284 "The origin for the sensor at (%.2f, %.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
290 if (publish_clearing_points)
301 #ifdef COSTMAP_2D_POINTCLOUD2
306 for (;iter_x != iter_x.
end(); ++iter_x, ++iter_y, ++iter_z)
308 double wpx = *iter_x;
309 double wpy = *iter_y;
310 double wpz = *iter_z;
312 pcl::PointCloud<pcl::PointXYZ>::const_iterator point_it = clearing_observation.
cloud_->begin();
313 for (;point_it < clearing_observation.
cloud_->end(); ++point_it) {
314 double wpx = point_it->x;
315 double wpy = point_it->y;
316 double wpz = point_it->z;
320 double scaling_fact = 1.0, scaling_fact_z = 1.0;
323 wpx = scaling_fact * (wpx - ox) + ox;
324 wpy = scaling_fact * (wpy - oy) + oy;
325 wpz = scaling_fact_z * (wpz - oz) + oz;
349 t = std::min(
t, (map_end_x - ox) / a);
353 t = std::min(
t, (map_end_y - oy) / b);
357 t = std::min(
t, (map_end_z - oz) / c);
364 double point_x, point_y, point_z;
372 cell_raytrace_range);
376 if (publish_clearing_points)
378 geometry_msgs::Point32 point;
387 if (publish_clearing_points)
390 #ifdef COSTMAP_2D_POINTCLOUD2
407 geometry_msgs::TransformStamped transformStamped;
408 #ifdef COSTMAP_2D_POINTCLOUD2
415 const double robot_z = transformStamped.transform.translation.z;
417 const double new_origin_z = robot_z - z_grid_height / 2;
420 #ifdef COSTMAP_2D_POINTCLOUD2
432 int cell_ox, cell_oy;
438 double new_grid_ox, new_grid_oy, new_grid_oz;
448 int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
449 lower_left_x = std::min(std::max(cell_ox, 0), size_x);
450 lower_left_y = std::min(std::max(cell_oy, 0), size_y);
451 upper_right_x = std::min(std::max(cell_ox + size_x, 0), size_x);
452 upper_right_y = std::min(std::max(cell_oy + size_y, 0), size_y);
454 unsigned int cell_size_x = upper_right_x - lower_left_x;
455 unsigned int cell_size_y = upper_right_y - lower_left_y;
458 unsigned char* local_map =
new unsigned char[cell_size_x * cell_size_y];
459 unsigned int* local_voxel_map =
new unsigned int[cell_size_x * cell_size_y];
464 copyMapRegion(voxel_map, lower_left_x, lower_left_y,
size_x_, local_voxel_map, 0, 0, cell_size_x, cell_size_x,
476 int start_x = lower_left_x - cell_ox;
477 int start_y = lower_left_y - cell_oy;
481 copyMapRegion3D(local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y,
size_x_, cell_size_x, cell_size_y, cell_oz);
485 delete[] local_voxel_map;