costmap_2d
obstacle_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  *********************************************************************/
40 #include <tf2_ros/message_filter.h>
41 
42 #include <pluginlib/class_list_macros.hpp>
43 #include <sensor_msgs/point_cloud2_iterator.h>
44 
45 PLUGINLIB_EXPORT_CLASS(costmap_2d::ObstacleLayer, costmap_2d::Layer)
46 
50 
53 
54 namespace costmap_2d
55 {
56 
58 {
59  ros::NodeHandle nh("~/" + name_), g_nh;
61 
62  bool track_unknown_space;
63  nh.param("track_unknown_space", track_unknown_space, layered_costmap_->isTrackingUnknown());
64  if (track_unknown_space)
66  else
68 
70  current_ = true;
71 
73  double transform_tolerance;
74  nh.param("transform_tolerance", transform_tolerance, 0.2);
75 
76  std::string topics_string;
77  // get the topics that we'll subscribe to from the parameter server
78  nh.param("observation_sources", topics_string, std::string(""));
79  ROS_INFO(" Subscribed to Topics: %s", topics_string.c_str());
80 
81  // now we need to split the topics based on whitespace which we can use a stringstream for
82  std::stringstream ss(topics_string);
83 
84  std::string source;
85  while (ss >> source)
86  {
87  ros::NodeHandle source_node(nh, source);
88 
89  // get the parameters for the specific topic
90  double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
91  std::string topic, sensor_frame, data_type;
92  bool inf_is_valid, clearing, marking;
93 
94  source_node.param("topic", topic, source);
95  source_node.param("sensor_frame", sensor_frame, std::string(""));
96  source_node.param("observation_persistence", observation_keep_time, 0.0);
97  source_node.param("expected_update_rate", expected_update_rate, 0.0);
98  source_node.param("data_type", data_type, std::string("PointCloud"));
99  source_node.param("min_obstacle_height", min_obstacle_height, 0.0);
100  source_node.param("max_obstacle_height", max_obstacle_height, 2.0);
101  source_node.param("inf_is_valid", inf_is_valid, false);
102  source_node.param("clearing", clearing, false);
103  source_node.param("marking", marking, true);
104 
105  if (!(data_type == "PointCloud2" || data_type == "PointCloud" || data_type == "LaserScan"))
106  {
107  ROS_FATAL("Only topics that use point clouds or laser scans are currently supported");
108  throw std::runtime_error("Only topics that use point clouds or laser scans are currently supported");
109  }
110 
111  std::string raytrace_range_param_name, obstacle_range_param_name;
112 
113  // get the obstacle range for the sensor
114  double obstacle_range = 2.5;
115  if (source_node.searchParam("obstacle_range", obstacle_range_param_name))
116  {
117  source_node.getParam(obstacle_range_param_name, obstacle_range);
118  }
119 
120  // get the raytrace range for the sensor
121  double raytrace_range = 3.0;
122  if (source_node.searchParam("raytrace_range", raytrace_range_param_name))
123  {
124  source_node.getParam(raytrace_range_param_name, raytrace_range);
125  }
126 
127  ROS_DEBUG("Creating an observation buffer for source %s, topic %s, frame %s", source.c_str(), topic.c_str(),
128  sensor_frame.c_str());
129 
130  // create an observation buffer
132  boost::shared_ptr < ObservationBuffer
133  > (new ObservationBuffer(topic, observation_keep_time, expected_update_rate, min_obstacle_height,
134  max_obstacle_height, obstacle_range, raytrace_range, *tf_, global_frame_,
135  sensor_frame, transform_tolerance)));
136 
137  // check if we'll add this buffer to our marking observation buffers
138  if (marking)
140 
141  // check if we'll also add this buffer to our clearing observation buffers
142  if (clearing)
144 
145  ROS_DEBUG(
146  "Created an observation buffer for source %s, topic %s, global frame: %s, "
147  "expected update rate: %.2f, observation persistence: %.2f",
148  source.c_str(), topic.c_str(), global_frame_.c_str(), expected_update_rate, observation_keep_time);
149 
150  // create a callback for the topic
151  if (data_type == "LaserScan")
152  {
153  boost::shared_ptr < message_filters::Subscriber<sensor_msgs::LaserScan>
154  > sub(new message_filters::Subscriber<sensor_msgs::LaserScan>(g_nh, topic, 50));
155 
156  boost::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::LaserScan> > filter(
157  new tf2_ros::MessageFilter<sensor_msgs::LaserScan>(*sub, *tf_, global_frame_, 50, g_nh));
158 
159  if (inf_is_valid)
160  {
161  filter->registerCallback([this,buffer=observation_buffers_.back()](auto& msg){ laserScanValidInfCallback(msg, buffer); });
162  }
163  else
164  {
165  filter->registerCallback([this,buffer=observation_buffers_.back()](auto& msg){ laserScanCallback(msg, buffer); });
166  }
167 
170 
171  observation_notifiers_.back()->setTolerance(ros::Duration(0.05));
172  }
173  else if (data_type == "PointCloud")
174  {
175  boost::shared_ptr < message_filters::Subscriber<sensor_msgs::PointCloud>
176  > sub(new message_filters::Subscriber<sensor_msgs::PointCloud>(g_nh, topic, 50));
177 
178  if (inf_is_valid)
179  {
180  ROS_WARN("obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
181  }
182 
183  boost::shared_ptr < tf2_ros::MessageFilter<sensor_msgs::PointCloud>
184  > filter(new tf2_ros::MessageFilter<sensor_msgs::PointCloud>(*sub, *tf_, global_frame_, 50, g_nh));
185  filter->registerCallback([this,buffer=observation_buffers_.back()](auto& msg){ pointCloudCallback(msg, buffer); });
186 
189  }
190  else
191  {
192  boost::shared_ptr < message_filters::Subscriber<sensor_msgs::PointCloud2>
193  > sub(new message_filters::Subscriber<sensor_msgs::PointCloud2>(g_nh, topic, 50));
194 
195  if (inf_is_valid)
196  {
197  ROS_WARN("obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
198  }
199 
200  boost::shared_ptr < tf2_ros::MessageFilter<sensor_msgs::PointCloud2>
201  > filter(new tf2_ros::MessageFilter<sensor_msgs::PointCloud2>(*sub, *tf_, global_frame_, 50, g_nh));
202  filter->registerCallback([this,buffer=observation_buffers_.back()](auto& msg){ pointCloud2Callback(msg, buffer); });
203 
206  }
207 
208  if (sensor_frame != "")
209  {
210  std::vector < std::string > target_frames;
211  target_frames.push_back(global_frame_);
212  target_frames.push_back(sensor_frame);
213  observation_notifiers_.back()->setTargetFrames(target_frames);
214  }
215  }
216 
217  dsrv_ = NULL;
219 }
220 
221 void ObstacleLayer::setupDynamicReconfigure(ros::NodeHandle& nh)
222 {
223  dsrv_ = new dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig>(nh);
224  dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig>::CallbackType cb =
225  [this](auto& config, auto level){ reconfigureCB(config, level); };
226  dsrv_->setCallback(cb);
227 }
228 
230 {
231  if (dsrv_)
232  delete dsrv_;
233 }
234 void ObstacleLayer::reconfigureCB(costmap_2d::ObstaclePluginConfig &config, uint32_t level)
235 {
236  enabled_ = config.enabled;
237  footprint_clearing_enabled_ = config.footprint_clearing_enabled;
238  max_obstacle_height_ = config.max_obstacle_height;
239  combination_method_ = config.combination_method;
240  occupied_to_default_time_ = config.occupied_to_default_time;
241  free_to_default_time_ = config.free_to_default_time;
242 }
243 
244 void ObstacleLayer::laserScanCallback(const sensor_msgs::LaserScanConstPtr& message,
245  const boost::shared_ptr<ObservationBuffer>& buffer)
246 {
247  // project the laser into a point cloud
248  sensor_msgs::PointCloud2 cloud;
249  cloud.header = message->header;
250 
251  // project the scan into a point cloud
252  try
253  {
254  projector_.transformLaserScanToPointCloud(message->header.frame_id, *message, cloud, *tf_);
255  }
256  catch (tf2::TransformException &ex)
257  {
258  ROS_WARN("High fidelity enabled, but TF returned a transform exception to frame %s: %s", global_frame_.c_str(),
259  ex.what());
260  projector_.projectLaser(*message, cloud);
261  }
262  catch (std::runtime_error &ex)
263  {
264  ROS_WARN("transformLaserScanToPointCloud error, it seems the message from laser sensor is malformed. Ignore this laser scan. what(): %s", ex.what());
265  return; //ignore this message
266  }
267 
268  // buffer the point cloud
269  buffer->lock();
270  buffer->bufferCloud(cloud);
271  buffer->unlock();
272 }
273 
274 void ObstacleLayer::laserScanValidInfCallback(const sensor_msgs::LaserScanConstPtr& raw_message,
275  const boost::shared_ptr<ObservationBuffer>& buffer)
276 {
277  // Filter positive infinities ("Inf"s) to max_range.
278  float epsilon = 0.0001; // a tenth of a millimeter
279  sensor_msgs::LaserScan message = *raw_message;
280  for (size_t i = 0; i < message.ranges.size(); i++)
281  {
282  float range = message.ranges[ i ];
283  if (!std::isfinite(range) && range > 0)
284  {
285  message.ranges[ i ] = message.range_max - epsilon;
286  }
287  }
288 
289  // project the laser into a point cloud
290  sensor_msgs::PointCloud2 cloud;
291  cloud.header = message.header;
292 
293  // project the scan into a point cloud
294  try
295  {
296  projector_.transformLaserScanToPointCloud(message.header.frame_id, message, cloud, *tf_);
297  }
298  catch (tf2::TransformException &ex)
299  {
300  ROS_WARN("High fidelity enabled, but TF returned a transform exception to frame %s: %s",
301  global_frame_.c_str(), ex.what());
302  projector_.projectLaser(message, cloud);
303  }
304  catch (std::runtime_error &ex)
305  {
306  ROS_WARN("transformLaserScanToPointCloud error, it seems the message from laser sensor is malformed. Ignore this laser scan. what(): %s", ex.what());
307  return; //ignore this message
308  }
309 
310  // buffer the point cloud
311  buffer->lock();
312  buffer->bufferCloud(cloud);
313  buffer->unlock();
314 }
315 
316 void ObstacleLayer::pointCloudCallback(const sensor_msgs::PointCloudConstPtr& message,
317  const boost::shared_ptr<ObservationBuffer>& buffer)
318 {
319  sensor_msgs::PointCloud2 cloud2;
320 
321  if (!sensor_msgs::convertPointCloudToPointCloud2(*message, cloud2))
322  {
323  ROS_ERROR("Failed to convert a PointCloud to a PointCloud2, dropping message");
324  return;
325  }
326 
327  // buffer the point cloud
328  buffer->lock();
329  buffer->bufferCloud(cloud2);
330  buffer->unlock();
331 }
332 
333 void ObstacleLayer::pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr& message,
334  const boost::shared_ptr<ObservationBuffer>& buffer)
335 {
336  // buffer the point cloud
337  buffer->lock();
338  buffer->bufferCloud(*message);
339  buffer->unlock();
340 }
341 
342 void ObstacleLayer::checkTimeStamps(double* min_x, double* min_y, double* max_x, double* max_y)
343 {
345  return;
346 
347  double wx, wy;
348  for (unsigned int mx = 0; mx < getSizeInCellsX(); ++mx)
349  {
350  for (unsigned int my = 0; my < getSizeInCellsY(); ++my)
351  {
352  unsigned char value = getCost(mx, my);
353 
354  if (value == FREE_SPACE || value == LETHAL_OBSTACLE)
355  {
356  double dt = ros::Time::now().toSec() - getTimeStamp(mx, my);
357 
358  if ( (dt > free_to_default_time_ && value == FREE_SPACE) ||
359  (dt > occupied_to_default_time_ && value == LETHAL_OBSTACLE) )
360  {
361  setCost(mx, my, NO_INFORMATION);
362  mapToWorld(mx, my, wx, wy);
363  touch(wx, wy, min_x, min_y, max_x, max_y);
364  }
365  }
366  }
367  }
368 }
369 
370 void ObstacleLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x,
371  double* min_y, double* max_x, double* max_y)
372 {
373  if (rolling_window_)
374  updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
375  useExtraBounds(min_x, min_y, max_x, max_y);
376 
377  checkTimeStamps(min_x, min_y, max_x, max_y);
378 
379  bool current = true;
380  std::vector<Observation> observations, clearing_observations;
381 
382  // get the marking observations
383  current = current && getMarkingObservations(observations);
384 
385  // get the clearing observations
386  current = current && getClearingObservations(clearing_observations);
387 
388  // update the global current status
389  current_ = current;
390 
391  // raytrace freespace
392  for (unsigned int i = 0; i < clearing_observations.size(); ++i)
393  {
394  raytraceFreespace(clearing_observations[i], min_x, min_y, max_x, max_y);
395  }
396 
397  // place the new obstacles into a priority queue... each with a priority of zero to begin with
398  for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
399  {
400  const Observation& obs = *it;
401 
402  const sensor_msgs::PointCloud2& cloud = *(obs.cloud_);
403 
404  double sq_obstacle_range = obs.obstacle_range_ * obs.obstacle_range_;
405 
406  sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud, "x");
407  sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud, "y");
408  sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud, "z");
409 
410  for (; iter_x !=iter_x.end(); ++iter_x, ++iter_y, ++iter_z)
411  {
412  double px = *iter_x, py = *iter_y, pz = *iter_z;
413 
414  // if the obstacle is too high or too far away from the robot we won't add it
415  if (pz > max_obstacle_height_)
416  {
417  ROS_DEBUG("The point is too high");
418  continue;
419  }
420 
421  // compute the squared distance from the hitpoint to the pointcloud's origin
422  double sq_dist = (px - obs.origin_.x) * (px - obs.origin_.x) + (py - obs.origin_.y) * (py - obs.origin_.y)
423  + (pz - obs.origin_.z) * (pz - obs.origin_.z);
424 
425  // if the point is far enough away... we won't consider it
426  if (sq_dist >= sq_obstacle_range)
427  {
428  ROS_DEBUG("The point is too far away");
429  continue;
430  }
431 
432  // now we need to compute the map coordinates for the observation
433  unsigned int mx, my;
434  if (!worldToMap(px, py, mx, my))
435  {
436  ROS_DEBUG("Computing map coords failed");
437  continue;
438  }
439 
440  setCost(mx, my, LETHAL_OBSTACLE);
441  touch(px, py, min_x, min_y, max_x, max_y);
442  }
443  }
444 
445  updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
446 }
447 
448 void ObstacleLayer::updateFootprint(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,
449  double* max_x, double* max_y)
450 {
451  if (!footprint_clearing_enabled_) return;
452  transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_);
453 
454  for (unsigned int i = 0; i < transformed_footprint_.size(); i++)
455  {
456  touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
457  }
458 }
459 
460 void ObstacleLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j)
461 {
463  {
465  }
466 
467  switch (combination_method_)
468  {
469  case 0: // Overwrite
470  updateWithOverwrite(master_grid, min_i, min_j, max_i, max_j);
471  break;
472  case 1: // Maximum
473  updateWithMax(master_grid, min_i, min_j, max_i, max_j);
474  break;
475  default: // Nothing
476  break;
477  }
478 }
479 
480 void ObstacleLayer::addStaticObservation(costmap_2d::Observation& obs, bool marking, bool clearing)
481 {
482  if (marking)
484  if (clearing)
486 }
487 
488 void ObstacleLayer::clearStaticObservations(bool marking, bool clearing)
489 {
490  if (marking)
492  if (clearing)
494 }
495 
497 {
498  bool current = true;
499  // get the marking observations
500  for (unsigned int i = 0; i < marking_buffers_.size(); ++i)
501  {
502  marking_buffers_[i]->lock();
503  marking_buffers_[i]->getObservations(marking_observations);
504  current = marking_buffers_[i]->isCurrent() && current;
505  marking_buffers_[i]->unlock();
506  }
507  marking_observations.insert(marking_observations.end(),
509  return current;
510 }
511 
513 {
514  bool current = true;
515  // get the clearing observations
516  for (unsigned int i = 0; i < clearing_buffers_.size(); ++i)
517  {
518  clearing_buffers_[i]->lock();
519  clearing_buffers_[i]->getObservations(clearing_observations);
520  current = clearing_buffers_[i]->isCurrent() && current;
521  clearing_buffers_[i]->unlock();
522  }
523  clearing_observations.insert(clearing_observations.end(),
525  return current;
526 }
527 
528 void ObstacleLayer::raytraceFreespace(const Observation& clearing_observation, double* min_x, double* min_y,
529  double* max_x, double* max_y)
530 {
531  double ox = clearing_observation.origin_.x;
532  double oy = clearing_observation.origin_.y;
533  const sensor_msgs::PointCloud2 &cloud = *(clearing_observation.cloud_);
534 
535  // get the map coordinates of the origin of the sensor
536  unsigned int x0, y0;
537  if (!worldToMap(ox, oy, x0, y0))
538  {
539  ROS_WARN_THROTTLE(
540  1.0, "The origin for the sensor at (%.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
541  ox, oy);
542  return;
543  }
544 
545  // we can pre-compute the enpoints of the map outside of the inner loop... we'll need these later
546  double origin_x = origin_x_, origin_y = origin_y_;
547  double map_end_x = origin_x + size_x_ * resolution_;
548  double map_end_y = origin_y + size_y_ * resolution_;
549 
550 
551  touch(ox, oy, min_x, min_y, max_x, max_y);
552 
553  // for each point in the cloud, we want to trace a line from the origin and clear obstacles along it
554  sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud, "x");
555  sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud, "y");
556 
557  for (; iter_x != iter_x.end(); ++iter_x, ++iter_y)
558  {
559  double wx = *iter_x;
560  double wy = *iter_y;
561 
562  // now we also need to make sure that the enpoint we're raytracing
563  // to isn't off the costmap and scale if necessary
564  double a = wx - ox;
565  double b = wy - oy;
566 
567  // the minimum value to raytrace from is the origin
568  if (wx < origin_x)
569  {
570  double t = (origin_x - ox) / a;
571  wx = origin_x;
572  wy = oy + b * t;
573  }
574  if (wy < origin_y)
575  {
576  double t = (origin_y - oy) / b;
577  wx = ox + a * t;
578  wy = origin_y;
579  }
580 
581  // the maximum value to raytrace to is the end of the map
582  if (wx > map_end_x)
583  {
584  double t = (map_end_x - ox) / a;
585  wx = map_end_x - .001;
586  wy = oy + b * t;
587  }
588  if (wy > map_end_y)
589  {
590  double t = (map_end_y - oy) / b;
591  wx = ox + a * t;
592  wy = map_end_y - .001;
593  }
594 
595  // now that the vector is scaled correctly... we'll get the map coordinates of its endpoint
596  unsigned int x1, y1;
597 
598  // check for legality just in case
599  if (!worldToMap(wx, wy, x1, y1))
600  continue;
601 
602  unsigned int cell_raytrace_range = cellDistance(clearing_observation.raytrace_range_);
603  MarkCell marker(costmap_, timestamps_, FREE_SPACE, ros::Time::now().toSec());
604  // and finally... we can execute our trace to clear obstacles along that line
605  raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_range);
606 
607  updateRaytraceBounds(ox, oy, wx, wy, clearing_observation.raytrace_range_, min_x, min_y, max_x, max_y);
608  }
609 }
610 
612 {
613  // if we're stopped we need to re-subscribe to topics
614  for (unsigned int i = 0; i < observation_subscribers_.size(); ++i)
615  {
616  if (observation_subscribers_[i] != NULL)
617  observation_subscribers_[i]->subscribe();
618  }
619 
620  for (unsigned int i = 0; i < observation_buffers_.size(); ++i)
621  {
622  if (observation_buffers_[i])
623  observation_buffers_[i]->resetLastUpdated();
624  }
625 }
627 {
628  for (unsigned int i = 0; i < observation_subscribers_.size(); ++i)
629  {
630  if (observation_subscribers_[i] != NULL)
631  observation_subscribers_[i]->unsubscribe();
632  }
633 }
634 
635 void ObstacleLayer::updateRaytraceBounds(double ox, double oy, double wx, double wy, double range,
636  double* min_x, double* min_y, double* max_x, double* max_y)
637 {
638  double dx = wx-ox, dy = wy-oy;
639  double full_distance = hypot(dx, dy);
640  double scale = std::min(1.0, range / full_distance);
641  double ex = ox + dx * scale, ey = oy + dy * scale;
642  touch(ex, ey, min_x, min_y, max_x, max_y);
643 }
644 
646 {
647  deactivate();
648  resetMaps();
649  current_ = true;
650  activate();
651 }
652 
653 } // namespace costmap_2d
costmap_2d::Costmap2D::timestamps_
double * timestamps_
Definition: costmap_2d.h:473
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::ObstacleLayer::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: obstacle_layer.cpp:528
costmap_2d::ObstacleLayer::global_frame_
std::string global_frame_
The global frame for the costmap.
Definition: obstacle_layer.h:229
obstacle_layer.h
std::string
costmap_2d::CostmapLayer::updateWithMax
void updateWithMax(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Definition: costmap_layer.cpp:63
costmap_2d::Layer::tf_
tf2_ros::Buffer * tf_
Definition: layer.h:178
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::ObstacleLayer::static_clearing_observations_
std::vector< costmap_2d::Observation > static_clearing_observations_
Definition: obstacle_layer.h:241
costmap_2d::Layer::enabled_
bool enabled_
Definition: layer.h:176
costmap_2d::ObstacleLayer::updateCosts
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Actually update the underlying costmap, only within the bounds calculated during UpdateBounds().
Definition: obstacle_layer.cpp:460
costmap_2d::LayeredCostmap::isRolling
bool isRolling()
Definition: layered_costmap.h:133
costmap_2d::ObstacleLayer::occupied_to_default_time_
double occupied_to_default_time_
Definition: obstacle_layer.h:192
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::MarkCell
Definition: costmap_2d.h:475
costmap_2d::Costmap2D::default_value_
unsigned char default_value_
Definition: costmap_2d.h:471
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::ObstacleLayer::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: obstacle_layer.cpp:370
costmap_2d::NO_INFORMATION
static const unsigned char NO_INFORMATION
Definition: cost_values.h:77
costmap_2d::Costmap2D::origin_x_
double origin_x_
Definition: costmap_2d.h:468
costmap_2d::transformFootprint
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::Point > &footprint_spec, std::vector< geometry_msgs::Point > &oriented_footprint)
Given a pose and base footprint, build the oriented footprint of the robot (list of Points)
Definition: footprint.cpp:106
std::stringstream
costmap_2d::ObstacleLayer::static_marking_observations_
std::vector< costmap_2d::Observation > static_marking_observations_
Definition: obstacle_layer.h:241
costmap_2d::ObstacleLayer::reconfigureCB
void reconfigureCB(costmap_2d::ObstaclePluginConfig &config, uint32_t level)
Definition: obstacle_layer.cpp:234
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::ObstacleLayer::observation_notifiers_
std::vector< boost::shared_ptr< tf2_ros::MessageFilterBase > > observation_notifiers_
Used to make sure that transforms are available for each sensor.
Definition: obstacle_layer.h:235
costmap_2d::Costmap2D
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.h:96
std::vector::back
T back(T... args)
costmap_2d::Costmap2D::mapToWorld
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
Definition: costmap_2d.cpp:218
costmap_2d::ObstacleLayer::projector_
laser_geometry::LaserProjection projector_
Used to project laser scans into point clouds.
Definition: obstacle_layer.h:232
costmap_2d::CostmapLayer::updateWithOverwrite
void updateWithOverwrite(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Definition: costmap_layer.cpp:108
costmap_2d::ObstacleLayer::setupDynamicReconfigure
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
Definition: obstacle_layer.cpp:221
costmap_2d::Layer::name_
std::string name_
Definition: layer.h:177
costmap_2d::ObstacleLayer::addStaticObservation
void addStaticObservation(costmap_2d::Observation &obs, bool marking, bool clearing)
Definition: obstacle_layer.cpp:480
costmap_2d::Layer::current_
bool current_
Definition: layer.h:175
costmap_2d::LayeredCostmap::isTrackingUnknown
bool isTrackingUnknown()
Definition: layered_costmap.h:138
costmap_2d::Layer::layered_costmap_
LayeredCostmap * layered_costmap_
Definition: layer.h:174
std::vector::clear
T clear(T... args)
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::free_to_default_time_
double free_to_default_time_
Definition: obstacle_layer.h:191
std::vector::push_back
T push_back(T... args)
costmap_2d::ObstacleLayer::max_obstacle_height_
double max_obstacle_height_
Max Obstacle Height.
Definition: obstacle_layer.h:230
costmap_2d::ObstacleLayer::marking_buffers_
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > marking_buffers_
Used to store observation buffers used for marking obstacles.
Definition: obstacle_layer.h:237
std::isfinite
T isfinite(T... args)
costmap_2d::ObstacleLayer::observation_subscribers_
std::vector< boost::shared_ptr< message_filters::SubscriberBase > > observation_subscribers_
Used for the observation message filters.
Definition: obstacle_layer.h:234
costmap_2d::ObstacleLayer::clearing_buffers_
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > clearing_buffers_
Used to store observation buffers used for clearing obstacles.
Definition: obstacle_layer.h:238
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
std::string::c_str
T c_str(T... args)
costmap_2d::ObstacleLayer::combination_method_
int combination_method_
Definition: obstacle_layer.h:246
costmap_2d::ObstacleLayer::transformed_footprint_
std::vector< geometry_msgs::Point > transformed_footprint_
Definition: obstacle_layer.h:224
costmap_2d::Costmap2D::size_y_
unsigned int size_y_
Definition: costmap_2d.h:466
costmap_2d::Costmap2D::getSizeInCellsY
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:456
costmap_2d::ObstacleLayer
Definition: obstacle_layer.h:98
std::runtime_error
costmap_2d::LETHAL_OBSTACLE
static const unsigned char LETHAL_OBSTACLE
Definition: cost_values.h:78
costmap_2d::ObstacleLayer::checkTimeStamps
void checkTimeStamps(double *min_x, double *min_y, double *max_x, double *max_y)
Definition: obstacle_layer.cpp:342
costmap_2d::Observation::obstacle_range_
double obstacle_range_
Definition: observation.h:98
costmap_2d::ObstacleLayer::~ObstacleLayer
virtual ~ObstacleLayer()
Definition: obstacle_layer.cpp:229
costmap_math.h
costmap_2d::Layer::getFootprint
const std::vector< geometry_msgs::Point > & getFootprint() const
Convenience function for layered_costmap_->getFootprint().
Definition: layer.cpp:51
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::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)
costmap_2d::ObstacleLayer::laserScanValidInfCallback
void laserScanValidInfCallback(const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< ObservationBuffer > &buffer)
A callback to handle buffering LaserScan messages which need filtering to turn Inf values into range_...
Definition: obstacle_layer.cpp:274
std::vector::insert
T insert(T... args)
costmap_2d::Costmap2D::resetMaps
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
Definition: costmap_2d.cpp:90
costmap_2d::ObstacleLayer::reset
virtual void reset()
Definition: obstacle_layer.cpp:645
costmap_2d::Costmap2D::raytraceLine
void raytraceLine(ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX)
Raytrace a line and apply some action at each step.
Definition: costmap_2d.h:404
costmap_2d::ObstacleLayer::pointCloud2Callback
void pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering PointCloud2 messages.
Definition: obstacle_layer.cpp:333
costmap_2d::Costmap2D::getTimeStamp
double getTimeStamp(unsigned int mx, unsigned int my) const
Get the last update timestamp of the cell.
Definition: costmap_2d.cpp:207
costmap_2d::ObstacleLayer::dsrv_
dynamic_reconfigure::Server< costmap_2d::ObstaclePluginConfig > * dsrv_
Definition: obstacle_layer.h:244
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::updateOrigin
virtual 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: costmap_2d.cpp:276
costmap_2d::Costmap2D::setConvexPolygonCost
bool setConvexPolygonCost(const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
Sets the cost of a convex polygon to a desired value.
Definition: costmap_2d.cpp:335
std::vector::end
T end(T... args)
costmap_2d::Costmap2D::costmap_
unsigned char * costmap_
Definition: costmap_2d.h:470
costmap_2d::ObstacleLayer::pointCloudCallback
void pointCloudCallback(const sensor_msgs::PointCloudConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering PointCloud messages.
Definition: obstacle_layer.cpp:316
costmap_2d::FREE_SPACE
static const unsigned char FREE_SPACE
Definition: cost_values.h:80
costmap_2d::Costmap2D::getSizeInCellsX
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:451
costmap_2d::LayeredCostmap::getGlobalFrameID
const std::string & getGlobalFrameID() const noexcept
Definition: layered_costmap.h:110
costmap_2d::ObstacleLayer::clearStaticObservations
void clearStaticObservations(bool marking, bool clearing)
Definition: obstacle_layer.cpp:488
costmap_2d::Costmap2D::getCost
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:202
costmap_2d::ObstacleLayer::footprint_clearing_enabled_
bool footprint_clearing_enabled_
Definition: obstacle_layer.h:225
costmap_2d
Definition: array_parser.h:37
costmap_2d::ObstacleLayer::laserScanCallback
void laserScanCallback(const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering LaserScan messages.
Definition: obstacle_layer.cpp:244
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::ObstacleLayer::observation_buffers_
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > observation_buffers_
Used to store observations from various sensors.
Definition: obstacle_layer.h:236
std::runtime_error::what
T what(T... args)
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