39 #include <pluginlib/class_list_macros.hpp>
40 #include <sensor_msgs/point_cloud2_iterator.h>
58 ros::NodeHandle private_nh(
"~/" +
name_);
62 voxel_pub_ = private_nh.advertise < costmap_2d::VoxelGrid > (
"voxel_grid", 1);
69 voxel_dsrv_ =
new dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>(nh);
70 dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>::CallbackType cb =
71 [
this](
auto& config,
auto level){
reconfigureCB(config, level); };
117 double* min_y,
double* max_x,
double* max_y)
136 for (
unsigned int i = 0; i < clearing_observations.
size(); ++i)
146 const sensor_msgs::PointCloud2& cloud = *(obs.
cloud_);
150 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
151 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
152 sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud,
"z");
154 for (
unsigned int i = 0; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z)
161 double sq_dist = (*iter_x - obs.
origin_.x) * (*iter_x - obs.
origin_.x)
166 if (sq_dist >= sq_obstacle_range)
170 unsigned int mx, my, mz;
176 else if (!
worldToMap3D(*iter_x, *iter_y, *iter_z, mx, my, mz))
185 touch(
double(*iter_x),
double(*iter_y), min_x, min_y, max_x, max_y);
192 costmap_2d::VoxelGrid grid_msg;
197 grid_msg.data.resize(size);
198 memcpy(&grid_msg.data[0],
voxel_grid_.getData(), size *
sizeof(
unsigned int));
208 grid_msg.header.stamp = ros::Time::now();
212 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
223 double start_x = wx - w_size_x / 2;
224 double start_y = wy - w_size_y / 2;
225 double end_x = start_x + w_size_x;
226 double end_y = start_y + w_size_y;
236 unsigned int map_sx, map_sy, map_ex, map_ey;
243 unsigned int index =
getIndex(map_sx, map_sy);
244 unsigned char* current = &
costmap_[index];
245 for (
unsigned int j = map_sy; j <= map_ey; ++j)
247 for (
unsigned int i = map_sx; i <= map_ex; ++i)
261 current +=
size_x_ - (map_ex - map_sx) - 1;
262 index +=
size_x_ - (map_ex - map_sx) - 1;
267 double* max_x,
double* max_y)
269 size_t clearing_observation_cloud_size = clearing_observation.
cloud_->height * clearing_observation.
cloud_->width;
270 if (clearing_observation_cloud_size == 0)
273 double sensor_x, sensor_y, sensor_z;
274 double ox = clearing_observation.
origin_.x;
275 double oy = clearing_observation.
origin_.y;
276 double oz = clearing_observation.
origin_.z;
282 "The origin for the sensor at (%.2f, %.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
288 if (publish_clearing_points)
298 sensor_msgs::PointCloud2ConstIterator<float> iter_x(*(clearing_observation.
cloud_),
"x");
299 sensor_msgs::PointCloud2ConstIterator<float> iter_y(*(clearing_observation.
cloud_),
"y");
300 sensor_msgs::PointCloud2ConstIterator<float> iter_z(*(clearing_observation.
cloud_),
"z");
302 for (;iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z)
304 double wpx = *iter_x;
305 double wpy = *iter_y;
306 double wpz = *iter_z;
309 double scaling_fact = 1.0;
311 wpx = scaling_fact * (wpx - ox) + ox;
312 wpy = scaling_fact * (wpy - oy) + oy;
313 wpz = scaling_fact * (wpz - oz) + oz;
346 t =
std::min(t, (map_end_x - ox) / a);
350 t =
std::min(t, (map_end_y - oy) / b);
357 double point_x, point_y, point_z;
363 voxel_grid_.clearVoxelLineInMap(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z,
costmap_,
365 cell_raytrace_range);
369 if (publish_clearing_points)
371 geometry_msgs::Point32 point;
380 if (publish_clearing_points)
393 int cell_ox, cell_oy;
399 double new_grid_ox, new_grid_oy;
408 int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
414 unsigned int cell_size_x = upper_right_x - lower_left_x;
415 unsigned int cell_size_y = upper_right_y - lower_left_y;
418 unsigned char* local_map =
new unsigned char[cell_size_x * cell_size_y];
419 unsigned int* local_voxel_map =
new unsigned int[cell_size_x * cell_size_y];
424 copyMapRegion(voxel_map, lower_left_x, lower_left_y,
size_x_, local_voxel_map, 0, 0, cell_size_x, cell_size_x,
435 int start_x = lower_left_x - cell_ox;
436 int start_y = lower_left_y - cell_oy;
440 copyMapRegion(local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y,
size_x_, cell_size_x, cell_size_y);
444 delete[] local_voxel_map;