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)
 
  124   std::vector<Observation> observations, clearing_observations;
 
  136   for (
unsigned int i = 0; i < clearing_observations.size(); ++i)
 
  142   for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
 
  146     const sensor_msgs::PointCloud2& cloud = *(obs.
cloud_);
 
  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))
 
  184         unsigned int index = 
getIndex(mx, my);
 
  187         touch(
double(*iter_x), 
double(*iter_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)
 
  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)
 
  304   for (;iter_x != iter_x.
end(); ++iter_x, ++iter_y, ++iter_z)
 
  306     double wpx = *iter_x;
 
  307     double wpy = *iter_y;
 
  308     double wpz = *iter_z;
 
  311     double scaling_fact = 1.0;
 
  313     wpx = scaling_fact * (wpx - ox) + ox;
 
  314     wpy = scaling_fact * (wpy - oy) + oy;
 
  315     wpz = scaling_fact * (wpz - oz) + oz;
 
  348       t = std::min(
t, (map_end_x - ox) / a);
 
  352       t = std::min(
t, (map_end_y - oy) / b);
 
  359     double point_x, point_y, point_z;
 
  367                                       cell_raytrace_range);
 
  371       if (publish_clearing_points)
 
  373         geometry_msgs::Point32 point;
 
  382   if (publish_clearing_points)
 
  395   int cell_ox, cell_oy;
 
  401   double new_grid_ox, new_grid_oy;
 
  410   int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
 
  411   lower_left_x = std::min(std::max(cell_ox, 0), size_x);
 
  412   lower_left_y = std::min(std::max(cell_oy, 0), size_y);
 
  413   upper_right_x = std::min(std::max(cell_ox + size_x, 0), size_x);
 
  414   upper_right_y = std::min(std::max(cell_oy + size_y, 0), size_y);
 
  416   unsigned int cell_size_x = upper_right_x - lower_left_x;
 
  417   unsigned int cell_size_y = upper_right_y - lower_left_y;
 
  420   unsigned char* local_map = 
new unsigned char[cell_size_x * cell_size_y];
 
  421   unsigned int* local_voxel_map = 
new unsigned int[cell_size_x * cell_size_y];
 
  426   copyMapRegion(voxel_map, lower_left_x, lower_left_y, 
size_x_, local_voxel_map, 0, 0, cell_size_x, cell_size_x,
 
  437   int start_x = lower_left_x - cell_ox;
 
  438   int start_y = lower_left_y - cell_oy;
 
  442   copyMapRegion(local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, 
size_x_, cell_size_x, cell_size_y);
 
  446   delete[] local_voxel_map;