costmap_2d
voxel_layer.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 #include <costmap_2d/voxel_layer.h>
39 #include <pluginlib/class_list_macros.hpp>
40 #include <sensor_msgs/point_cloud2_iterator.h>
41 
42 #define VOXEL_BITS 16
43 PLUGINLIB_EXPORT_CLASS(costmap_2d::VoxelLayer, costmap_2d::Layer)
44 
48 
51 
52 namespace costmap_2d
53 {
54 
56 {
58  ros::NodeHandle private_nh("~/" + name_);
59 
60  private_nh.param("publish_voxel_map", publish_voxel_, false);
61  if (publish_voxel_)
62  voxel_pub_ = private_nh.advertise < costmap_2d::VoxelGrid > ("voxel_grid", 1);
63 
64  clearing_endpoints_pub_ = private_nh.advertise<sensor_msgs::PointCloud>("clearing_endpoints", 1);
65 }
66 
67 void VoxelLayer::setupDynamicReconfigure(ros::NodeHandle& nh)
68 {
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); };
72  voxel_dsrv_->setCallback(cb);
73 }
74 
76 {
77  if (voxel_dsrv_)
78  delete voxel_dsrv_;
79 }
80 
81 void VoxelLayer::reconfigureCB(costmap_2d::VoxelPluginConfig &config, uint32_t level)
82 {
83  enabled_ = config.enabled;
84  footprint_clearing_enabled_ = config.footprint_clearing_enabled;
85  max_obstacle_height_ = config.max_obstacle_height;
86  size_z_ = config.z_voxels;
87  origin_z_ = config.origin_z;
88  z_resolution_ = config.z_resolution;
89  unknown_threshold_ = config.unknown_threshold + (VOXEL_BITS - size_z_);
90  mark_threshold_ = config.mark_threshold;
91  combination_method_ = config.combination_method;
92  matchSize();
93 }
94 
96 {
99  ROS_ASSERT(voxel_grid_.sizeX() == size_x_ && voxel_grid_.sizeY() == size_y_);
100 }
101 
103 {
104  deactivate();
105  resetMaps();
106  voxel_grid_.reset();
107  activate();
108 }
109 
111 {
113  voxel_grid_.reset();
114 }
115 
116 void VoxelLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x,
117  double* min_y, double* max_x, double* max_y)
118 {
119  if (rolling_window_)
120  updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
121  useExtraBounds(min_x, min_y, max_x, max_y);
122 
123  bool current = true;
124  std::vector<Observation> observations, clearing_observations;
125 
126  // get the marking observations
127  current = getMarkingObservations(observations) && current;
128 
129  // get the clearing observations
130  current = getClearingObservations(clearing_observations) && current;
131 
132  // update the global current status
133  current_ = current;
134 
135  // raytrace freespace
136  for (unsigned int i = 0; i < clearing_observations.size(); ++i)
137  {
138  raytraceFreespace(clearing_observations[i], min_x, min_y, max_x, max_y);
139  }
140 
141  // place the new obstacles into a priority queue... each with a priority of zero to begin with
142  for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
143  {
144  const Observation& obs = *it;
145 
146  const sensor_msgs::PointCloud2& cloud = *(obs.cloud_);
147 
148  double sq_obstacle_range = obs.obstacle_range_ * obs.obstacle_range_;
149 
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");
153 
154  for (unsigned int i = 0; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z)
155  {
156  // if the obstacle is too high or too far away from the robot we won't add it
157  if (*iter_z > max_obstacle_height_)
158  continue;
159 
160  // compute the squared distance from the hitpoint to the pointcloud's origin
161  double sq_dist = (*iter_x - obs.origin_.x) * (*iter_x - obs.origin_.x)
162  + (*iter_y - obs.origin_.y) * (*iter_y - obs.origin_.y)
163  + (*iter_z - obs.origin_.z) * (*iter_z - obs.origin_.z);
164 
165  // if the point is far enough away... we won't consider it
166  if (sq_dist >= sq_obstacle_range)
167  continue;
168 
169  // now we need to compute the map coordinates for the observation
170  unsigned int mx, my, mz;
171  if (*iter_z < origin_z_)
172  {
173  if (!worldToMap3D(*iter_x, *iter_y, origin_z_, mx, my, mz))
174  continue;
175  }
176  else if (!worldToMap3D(*iter_x, *iter_y, *iter_z, mx, my, mz))
177  {
178  continue;
179  }
180 
181  // mark the cell in the voxel grid and check if we should also mark it in the costmap
182  if (voxel_grid_.markVoxelInMap(mx, my, mz, mark_threshold_))
183  {
184  setCost(mx, my, LETHAL_OBSTACLE);
185  touch(double(*iter_x), double(*iter_y), min_x, min_y, max_x, max_y);
186  }
187  }
188  }
189 
190  if (publish_voxel_)
191  {
192  costmap_2d::VoxelGrid grid_msg;
193  unsigned int size = voxel_grid_.sizeX() * voxel_grid_.sizeY();
194  grid_msg.size_x = voxel_grid_.sizeX();
195  grid_msg.size_y = voxel_grid_.sizeY();
196  grid_msg.size_z = voxel_grid_.sizeZ();
197  grid_msg.data.resize(size);
198  memcpy(&grid_msg.data[0], voxel_grid_.getData(), size * sizeof(unsigned int));
199 
200  grid_msg.origin.x = origin_x_;
201  grid_msg.origin.y = origin_y_;
202  grid_msg.origin.z = origin_z_;
203 
204  grid_msg.resolutions.x = resolution_;
205  grid_msg.resolutions.y = resolution_;
206  grid_msg.resolutions.z = z_resolution_;
207  grid_msg.header.frame_id = global_frame_;
208  grid_msg.header.stamp = ros::Time::now();
209  voxel_pub_.publish(grid_msg);
210  }
211 
212  updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
213 }
214 
215 void VoxelLayer::clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info)
216 {
217  // get the cell coordinates of the center point of the window
218  unsigned int mx, my;
219  if (!worldToMap(wx, wy, mx, my))
220  return;
221 
222  // compute the bounds of the window
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;
227 
228  // scale the window based on the bounds of the costmap
229  start_x = std::max(origin_x_, start_x);
230  start_y = std::max(origin_y_, start_y);
231 
232  end_x = std::min(origin_x_ + getSizeInMetersX(), end_x);
233  end_y = std::min(origin_y_ + getSizeInMetersY(), end_y);
234 
235  // get the map coordinates of the bounds of the window
236  unsigned int map_sx, map_sy, map_ex, map_ey;
237 
238  // check for legality just in case
239  if (!worldToMap(start_x, start_y, map_sx, map_sy) || !worldToMap(end_x, end_y, map_ex, map_ey))
240  return;
241 
242  // we know that we want to clear all non-lethal obstacles in this window to get it ready for inflation
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)
246  {
247  for (unsigned int i = map_sx; i <= map_ex; ++i)
248  {
249  // if the cell is a lethal obstacle... we'll keep it and queue it, otherwise... we'll clear it
250  if (*current != LETHAL_OBSTACLE)
251  {
252  if (clear_no_info || *current != NO_INFORMATION)
253  {
254  *current = FREE_SPACE;
255  voxel_grid_.clearVoxelColumn(index);
256  }
257  }
258  current++;
259  index++;
260  }
261  current += size_x_ - (map_ex - map_sx) - 1;
262  index += size_x_ - (map_ex - map_sx) - 1;
263  }
264 }
265 
266 void VoxelLayer::raytraceFreespace(const Observation& clearing_observation, double* min_x, double* min_y,
267  double* max_x, double* max_y)
268 {
269  size_t clearing_observation_cloud_size = clearing_observation.cloud_->height * clearing_observation.cloud_->width;
270  if (clearing_observation_cloud_size == 0)
271  return;
272 
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;
277 
278  if (!worldToMap3DFloat(ox, oy, oz, sensor_x, sensor_y, sensor_z))
279  {
280  ROS_WARN_THROTTLE(
281  1.0,
282  "The origin for the sensor at (%.2f, %.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
283  ox, oy, oz);
284  return;
285  }
286 
287  bool publish_clearing_points = (clearing_endpoints_pub_.getNumSubscribers() > 0);
288  if (publish_clearing_points)
289  {
290  clearing_endpoints_.points.clear();
291  clearing_endpoints_.points.reserve(clearing_observation_cloud_size);
292  }
293 
294  // we can pre-compute the enpoints of the map outside of the inner loop... we'll need these later
295  double map_end_x = origin_x_ + getSizeInMetersX();
296  double map_end_y = origin_y_ + getSizeInMetersY();
297 
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");
301 
302  for (;iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z)
303  {
304  double wpx = *iter_x;
305  double wpy = *iter_y;
306  double wpz = *iter_z;
307 
308  double distance = dist(ox, oy, oz, wpx, wpy, wpz);
309  double scaling_fact = 1.0;
310  scaling_fact = std::max(std::min(scaling_fact, (distance - 2 * resolution_) / distance), 0.0);
311  wpx = scaling_fact * (wpx - ox) + ox;
312  wpy = scaling_fact * (wpy - oy) + oy;
313  wpz = scaling_fact * (wpz - oz) + oz;
314 
315  double a = wpx - ox;
316  double b = wpy - oy;
317  double c = wpz - oz;
318  double t = 1.0;
319 
320  // we can only raytrace to a maximum z height
321  if (wpz > max_obstacle_height_)
322  {
323  // we know we want the vector's z value to be max_z
324  t = std::max(0.0, std::min(t, (max_obstacle_height_ - 0.01 - oz) / c));
325  }
326  // and we can only raytrace down to the floor
327  else if (wpz < origin_z_)
328  {
329  // we know we want the vector's z value to be 0.0
330  t = std::min(t, (origin_z_ - oz) / c);
331  }
332 
333  // the minimum value to raytrace from is the origin
334  if (wpx < origin_x_)
335  {
336  t = std::min(t, (origin_x_ - ox) / a);
337  }
338  if (wpy < origin_y_)
339  {
340  t = std::min(t, (origin_y_ - oy) / b);
341  }
342 
343  // the maximum value to raytrace to is the end of the map
344  if (wpx > map_end_x)
345  {
346  t = std::min(t, (map_end_x - ox) / a);
347  }
348  if (wpy > map_end_y)
349  {
350  t = std::min(t, (map_end_y - oy) / b);
351  }
352 
353  wpx = ox + a * t;
354  wpy = oy + b * t;
355  wpz = oz + c * t;
356 
357  double point_x, point_y, point_z;
358  if (worldToMap3DFloat(wpx, wpy, wpz, point_x, point_y, point_z))
359  {
360  unsigned int cell_raytrace_range = cellDistance(clearing_observation.raytrace_range_);
361 
362  // voxel_grid_.markVoxelLine(sensor_x, sensor_y, sensor_z, 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);
366 
367  updateRaytraceBounds(ox, oy, wpx, wpy, clearing_observation.raytrace_range_, min_x, min_y, max_x, max_y);
368 
369  if (publish_clearing_points)
370  {
371  geometry_msgs::Point32 point;
372  point.x = wpx;
373  point.y = wpy;
374  point.z = wpz;
375  clearing_endpoints_.points.push_back(point);
376  }
377  }
378  }
379 
380  if (publish_clearing_points)
381  {
382  clearing_endpoints_.header.frame_id = global_frame_;
383  clearing_endpoints_.header.stamp = clearing_observation.cloud_->header.stamp;
384  clearing_endpoints_.header.seq = clearing_observation.cloud_->header.seq;
385 
387  }
388 }
389 
390 void VoxelLayer::updateOrigin(double new_origin_x, double new_origin_y)
391 {
392  // project the new origin into the grid
393  int cell_ox, cell_oy;
394  cell_ox = int((new_origin_x - origin_x_) / resolution_);
395  cell_oy = int((new_origin_y - origin_y_) / resolution_);
396 
397  // compute the associated world coordinates for the origin cell
398  // beacuase we want to keep things grid-aligned
399  double new_grid_ox, new_grid_oy;
400  new_grid_ox = origin_x_ + cell_ox * resolution_;
401  new_grid_oy = origin_y_ + cell_oy * resolution_;
402 
403  // To save casting from unsigned int to int a bunch of times
404  int size_x = size_x_;
405  int size_y = size_y_;
406 
407  // we need to compute the overlap of the new and existing windows
408  int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
409  lower_left_x = std::min(std::max(cell_ox, 0), size_x);
410  lower_left_y = std::min(std::max(cell_oy, 0), size_y);
411  upper_right_x = std::min(std::max(cell_ox + size_x, 0), size_x);
412  upper_right_y = std::min(std::max(cell_oy + size_y, 0), size_y);
413 
414  unsigned int cell_size_x = upper_right_x - lower_left_x;
415  unsigned int cell_size_y = upper_right_y - lower_left_y;
416 
417  // we need a map to store the obstacles in the window temporarily
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];
420  unsigned int* voxel_map = voxel_grid_.getData();
421 
422  // copy the local window in the costmap to the local map
423  copyMapRegion(costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, 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,
425  cell_size_y);
426 
427  // we'll reset our maps to unknown space if appropriate
428  resetMaps();
429 
430  // update the origin with the appropriate world coordinates
431  origin_x_ = new_grid_ox;
432  origin_y_ = new_grid_oy;
433 
434  // compute the starting cell location for copying data back in
435  int start_x = lower_left_x - cell_ox;
436  int start_y = lower_left_y - cell_oy;
437 
438  // now we want to copy the overlapping information back into the map, but in its new location
439  copyMapRegion(local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y);
440  copyMapRegion(local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_, cell_size_x, cell_size_y);
441 
442  // make sure to clean up
443  delete[] local_map;
444  delete[] local_voxel_map;
445 }
446 
447 } // namespace costmap_2d
costmap_2d::Costmap2D::getSizeInMetersX
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
Definition: costmap_2d.cpp:461
costmap_2d::ObstacleLayer::deactivate
virtual void deactivate()
Stop publishers.
Definition: obstacle_layer.cpp:626
costmap_2d::ObstacleLayer::getMarkingObservations
bool getMarkingObservations(std::vector< costmap_2d::Observation > &marking_observations) const
Get the observations used to mark space.
Definition: obstacle_layer.cpp:496
costmap_2d::VoxelLayer::origin_z_
double origin_z_
Definition: voxel_layer.h:173
costmap_2d::VoxelLayer
Definition: voxel_layer.h:97
costmap_2d::ObstacleLayer::global_frame_
std::string global_frame_
The global frame for the costmap.
Definition: obstacle_layer.h:229
costmap_2d::VoxelLayer::reconfigureCB
void reconfigureCB(costmap_2d::VoxelPluginConfig &config, uint32_t level)
Definition: voxel_layer.cpp:81
costmap_2d::VoxelLayer::raytraceFreespace
virtual void raytraceFreespace(const costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y)
Clear freespace based on one observation.
Definition: voxel_layer.cpp:266
costmap_2d::Observation::raytrace_range_
double raytrace_range_
Definition: observation.h:98
costmap_2d::ObstacleLayer::updateRaytraceBounds
void updateRaytraceBounds(double ox, double oy, double wx, double wy, double range, double *min_x, double *min_y, double *max_x, double *max_y)
Definition: obstacle_layer.cpp:635
costmap_2d::VoxelLayer::resetMaps
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
Definition: voxel_layer.cpp:110
costmap_2d::Layer::enabled_
bool enabled_
Definition: layer.h:176
costmap_2d::Costmap2D::worldToMap
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:224
costmap_2d::Costmap2D::getSizeInMetersY
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
Definition: costmap_2d.cpp:466
std::vector
std::vector::size
T size(T... args)
costmap_2d::VoxelLayer::dist
double dist(double x0, double y0, double z0, double x1, double y1, double z1)
Definition: voxel_layer.h:214
VOXEL_BITS
#define VOXEL_BITS
Definition: voxel_layer.cpp:42
costmap_2d::VoxelLayer::worldToMap3DFloat
bool worldToMap3DFloat(double wx, double wy, double wz, double &mx, double &my, double &mz)
Definition: voxel_layer.h:178
costmap_2d::NO_INFORMATION
static const unsigned char NO_INFORMATION
Definition: cost_values.h:77
costmap_2d::VoxelLayer::voxel_grid_
voxel_grid::VoxelGrid voxel_grid_
Definition: voxel_layer.h:172
costmap_2d::Costmap2D::origin_x_
double origin_x_
Definition: costmap_2d.h:468
costmap_2d::CostmapLayer::matchSize
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
Definition: costmap_layer.cpp:14
costmap_2d::VoxelLayer::worldToMap3D
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
Definition: voxel_layer.h:191
costmap_2d::VoxelLayer::updateBounds
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to up...
Definition: voxel_layer.cpp:116
costmap_2d::VoxelLayer::z_resolution_
double z_resolution_
Definition: voxel_layer.h:173
costmap_2d::Layer::name_
std::string name_
Definition: layer.h:177
costmap_2d::Layer::current_
bool current_
Definition: layer.h:175
costmap_2d::VoxelLayer::voxel_pub_
ros::Publisher voxel_pub_
Definition: voxel_layer.h:171
costmap_2d::ObstacleLayer::onInitialize
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
Definition: obstacle_layer.cpp:57
costmap_2d::Observation::cloud_
sensor_msgs::PointCloud2 * cloud_
Definition: observation.h:97
costmap_2d::ObstacleLayer::max_obstacle_height_
double max_obstacle_height_
Max Obstacle Height.
Definition: obstacle_layer.h:230
costmap_2d::Costmap2D::setCost
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
Definition: costmap_2d.cpp:212
costmap_2d::ObstacleLayer::activate
virtual void activate()
Restart publishers if they've been stopped.
Definition: obstacle_layer.cpp:611
costmap_2d::VoxelLayer::reset
virtual void reset()
Definition: voxel_layer.cpp:102
costmap_2d::VoxelLayer::matchSize
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
Definition: voxel_layer.cpp:95
costmap_2d::VoxelLayer::setupDynamicReconfigure
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
Definition: voxel_layer.cpp:67
costmap_2d::ObstacleLayer::combination_method_
int combination_method_
Definition: obstacle_layer.h:246
costmap_2d::VoxelLayer::voxel_dsrv_
dynamic_reconfigure::Server< costmap_2d::VoxelPluginConfig > * voxel_dsrv_
Definition: voxel_layer.h:168
costmap_2d::Costmap2D::size_y_
unsigned int size_y_
Definition: costmap_2d.h:466
costmap_2d::VoxelLayer::unknown_threshold_
unsigned int unknown_threshold_
Definition: voxel_layer.h:174
costmap_2d::LETHAL_OBSTACLE
static const unsigned char LETHAL_OBSTACLE
Definition: cost_values.h:78
costmap_2d::Observation::obstacle_range_
double obstacle_range_
Definition: observation.h:98
distance
double distance(double x0, double y0, double x1, double y1)
Definition: costmap_math.h:58
costmap_2d::VoxelLayer::clearing_endpoints_pub_
ros::Publisher clearing_endpoints_pub_
Definition: voxel_layer.h:175
costmap_2d::ObstacleLayer::updateFootprint
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Definition: obstacle_layer.cpp:448
costmap_2d::CostmapLayer::useExtraBounds
void useExtraBounds(double *min_x, double *min_y, double *max_x, double *max_y)
Definition: costmap_layer.cpp:47
std::min
T min(T... args)
costmap_2d::Costmap2D::size_x_
unsigned int size_x_
Definition: costmap_2d.h:465
costmap_2d::CostmapLayer::touch
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
Definition: costmap_layer.cpp:6
costmap_2d::Costmap2D::cellDistance
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
Definition: costmap_2d.cpp:191
costmap_2d::VoxelLayer::clearNonLethal
void clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info)
Definition: voxel_layer.cpp:215
costmap_2d::VoxelLayer::publish_voxel_
bool publish_voxel_
Definition: voxel_layer.h:170
costmap_2d::Costmap2D::resolution_
double resolution_
Definition: costmap_2d.h:467
costmap_2d::Observation
Stores an observation in terms of a point cloud and the origin of the source.
Definition: observation.h:46
std::vector::begin
T begin(T... args)
voxel_layer.h
costmap_2d::Costmap2D::resetMaps
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
Definition: costmap_2d.cpp:90
costmap_2d::VoxelLayer::clearing_endpoints_
sensor_msgs::PointCloud clearing_endpoints_
Definition: voxel_layer.h:176
costmap_2d::VoxelLayer::onInitialize
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
Definition: voxel_layer.cpp:55
costmap_2d::VoxelLayer::updateOrigin
void updateOrigin(double new_origin_x, double new_origin_y)
Move the origin of the costmap to a new location.... keeping data when it can.
Definition: voxel_layer.cpp:390
costmap_2d::Costmap2D::copyMapRegion
void copyMapRegion(data_type *source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, unsigned int sm_size_x, data_type *dest_map, unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x, unsigned int region_size_y)
Copy a region of a source map into a destination map.
Definition: costmap_2d.h:359
costmap_2d::VoxelLayer::size_z_
unsigned int size_z_
Definition: voxel_layer.h:174
costmap_2d::Costmap2D::origin_y_
double origin_y_
Definition: costmap_2d.h:469
costmap_2d::Layer
Definition: layer.h:84
costmap_2d::Observation::origin_
geometry_msgs::Point origin_
Definition: observation.h:96
costmap_2d::Costmap2D::getIndex
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition: costmap_2d.h:215
std::vector::end
T end(T... args)
costmap_2d::Costmap2D::costmap_
unsigned char * costmap_
Definition: costmap_2d.h:470
costmap_2d::FREE_SPACE
static const unsigned char FREE_SPACE
Definition: cost_values.h:80
std::max
T max(T... args)
costmap_2d::VoxelLayer::mark_threshold_
unsigned int mark_threshold_
Definition: voxel_layer.h:174
costmap_2d::ObstacleLayer::footprint_clearing_enabled_
bool footprint_clearing_enabled_
Definition: obstacle_layer.h:225
costmap_2d
Definition: array_parser.h:37
costmap_2d::ObservationBuffer
Takes in point clouds from sensors, transforms them to the desired frame, and stores them.
Definition: observation_buffer.h:93
costmap_2d::VoxelLayer::~VoxelLayer
virtual ~VoxelLayer()
Definition: voxel_layer.cpp:75
costmap_2d::ObstacleLayer::rolling_window_
bool rolling_window_
Definition: obstacle_layer.h:243
costmap_2d::ObstacleLayer::getClearingObservations
bool getClearingObservations(std::vector< costmap_2d::Observation > &clearing_observations) const
Get the observations used to clear space.
Definition: obstacle_layer.cpp:512