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 
44 
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
131  observation_buffers_.push_back(
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)
139  marking_buffers_.push_back(observation_buffers_.back());
140 
141  // check if we'll also add this buffer to our clearing observation buffers
142  if (clearing)
143  clearing_buffers_.push_back(observation_buffers_.back());
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  {
154  > sub(new message_filters::Subscriber<sensor_msgs::LaserScan>(g_nh, topic, 50));
155 
158 
159  if (inf_is_valid)
160  {
161  filter->registerCallback(boost::bind(&ObstacleLayer::laserScanValidInfCallback, this, _1,
162  observation_buffers_.back()));
163  }
164  else
165  {
166  filter->registerCallback(boost::bind(&ObstacleLayer::laserScanCallback, this, _1, observation_buffers_.back()));
167  }
168 
169  observation_subscribers_.push_back(sub);
170  observation_notifiers_.push_back(filter);
171 
172  observation_notifiers_.back()->setTolerance(ros::Duration(0.05));
173  }
174  else if (data_type == "PointCloud")
175  {
177  > sub(new message_filters::Subscriber<sensor_msgs::PointCloud>(g_nh, topic, 50));
178 
179  if (inf_is_valid)
180  {
181  ROS_WARN("obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
182  }
183 
185  > filter(new tf2_ros::MessageFilter<sensor_msgs::PointCloud>(*sub, *tf_, global_frame_, 50, g_nh));
186  filter->registerCallback(
187  boost::bind(&ObstacleLayer::pointCloudCallback, this, _1, observation_buffers_.back()));
188 
189  observation_subscribers_.push_back(sub);
190  observation_notifiers_.push_back(filter);
191  }
192  else
193  {
195  > sub(new message_filters::Subscriber<sensor_msgs::PointCloud2>(g_nh, topic, 50));
196 
197  if (inf_is_valid)
198  {
199  ROS_WARN("obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
200  }
201 
203  > filter(new tf2_ros::MessageFilter<sensor_msgs::PointCloud2>(*sub, *tf_, global_frame_, 50, g_nh));
204  filter->registerCallback(
205  boost::bind(&ObstacleLayer::pointCloud2Callback, this, _1, observation_buffers_.back()));
206 
207  observation_subscribers_.push_back(sub);
208  observation_notifiers_.push_back(filter);
209  }
210 
211  if (sensor_frame != "")
212  {
213  std::vector < std::string > target_frames;
214  target_frames.push_back(global_frame_);
215  target_frames.push_back(sensor_frame);
216  observation_notifiers_.back()->setTargetFrames(target_frames);
217  }
218  }
219 
220  dsrv_ = NULL;
222 }
223 
225 {
226  dsrv_ = new dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig>(nh);
227  dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig>::CallbackType cb = boost::bind(
228  &ObstacleLayer::reconfigureCB, this, _1, _2);
229  dsrv_->setCallback(cb);
230 }
231 
233 {
234  if (dsrv_)
235  delete dsrv_;
236 }
237 void ObstacleLayer::reconfigureCB(costmap_2d::ObstaclePluginConfig &config, uint32_t level)
238 {
239  enabled_ = config.enabled;
240  footprint_clearing_enabled_ = config.footprint_clearing_enabled;
241  max_obstacle_height_ = config.max_obstacle_height;
242  combination_method_ = config.combination_method;
243 }
244 
245 void ObstacleLayer::laserScanCallback(const sensor_msgs::LaserScanConstPtr& message,
247 {
248  // project the laser into a point cloud
249  sensor_msgs::PointCloud2 cloud;
250  cloud.header = message->header;
251 
252  // project the scan into a point cloud
253  try
254  {
255  projector_.transformLaserScanToPointCloud(message->header.frame_id, *message, cloud, *tf_);
256  }
257  catch (tf2::TransformException &ex)
258  {
259  ROS_WARN("High fidelity enabled, but TF returned a transform exception to frame %s: %s", global_frame_.c_str(),
260  ex.what());
261  projector_.projectLaser(*message, cloud);
262  }
263 
264  // buffer the point cloud
265  buffer->lock();
266  buffer->bufferCloud(cloud);
267  buffer->unlock();
268 }
269 
270 void ObstacleLayer::laserScanValidInfCallback(const sensor_msgs::LaserScanConstPtr& raw_message,
272 {
273  // Filter positive infinities ("Inf"s) to max_range.
274  float epsilon = 0.0001; // a tenth of a millimeter
275  sensor_msgs::LaserScan message = *raw_message;
276  for (size_t i = 0; i < message.ranges.size(); i++)
277  {
278  float range = message.ranges[ i ];
279  if (!std::isfinite(range) && range > 0)
280  {
281  message.ranges[ i ] = message.range_max - epsilon;
282  }
283  }
284 
285  // project the laser into a point cloud
286  sensor_msgs::PointCloud2 cloud;
287  cloud.header = message.header;
288 
289  // project the scan into a point cloud
290  try
291  {
292  projector_.transformLaserScanToPointCloud(message.header.frame_id, message, cloud, *tf_);
293  }
294  catch (tf2::TransformException &ex)
295  {
296  ROS_WARN("High fidelity enabled, but TF returned a transform exception to frame %s: %s",
297  global_frame_.c_str(), ex.what());
298  projector_.projectLaser(message, cloud);
299  }
300 
301  // buffer the point cloud
302  buffer->lock();
303  buffer->bufferCloud(cloud);
304  buffer->unlock();
305 }
306 
307 void ObstacleLayer::pointCloudCallback(const sensor_msgs::PointCloudConstPtr& message,
309 {
310  sensor_msgs::PointCloud2 cloud2;
311 
312  if (!sensor_msgs::convertPointCloudToPointCloud2(*message, cloud2))
313  {
314  ROS_ERROR("Failed to convert a PointCloud to a PointCloud2, dropping message");
315  return;
316  }
317 
318  // buffer the point cloud
319  buffer->lock();
320  buffer->bufferCloud(cloud2);
321  buffer->unlock();
322 }
323 
324 void ObstacleLayer::pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr& message,
326 {
327  // buffer the point cloud
328  buffer->lock();
329  buffer->bufferCloud(*message);
330  buffer->unlock();
331 }
332 
333 void ObstacleLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x,
334  double* min_y, double* max_x, double* max_y)
335 {
336  if (rolling_window_)
337  updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
338  if (!enabled_)
339  return;
340  useExtraBounds(min_x, min_y, max_x, max_y);
341 
342  bool current = true;
343  std::vector<Observation> observations, clearing_observations;
344 
345  // get the marking observations
346  current = current && getMarkingObservations(observations);
347 
348  // get the clearing observations
349  current = current && getClearingObservations(clearing_observations);
350 
351  // update the global current status
352  current_ = current;
353 
354  // raytrace freespace
355  for (unsigned int i = 0; i < clearing_observations.size(); ++i)
356  {
357  raytraceFreespace(clearing_observations[i], min_x, min_y, max_x, max_y);
358  }
359 
360  // place the new obstacles into a priority queue... each with a priority of zero to begin with
361  for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
362  {
363  const Observation& obs = *it;
364 
365  const sensor_msgs::PointCloud2& cloud = *(obs.cloud_);
366 
367  double sq_obstacle_range = obs.obstacle_range_ * obs.obstacle_range_;
368 
372 
373  for (; iter_x !=iter_x.end(); ++iter_x, ++iter_y, ++iter_z)
374  {
375  double px = *iter_x, py = *iter_y, pz = *iter_z;
376 
377  // if the obstacle is too high or too far away from the robot we won't add it
378  if (pz > max_obstacle_height_)
379  {
380  ROS_DEBUG("The point is too high");
381  continue;
382  }
383 
384  // compute the squared distance from the hitpoint to the pointcloud's origin
385  double sq_dist = (px - obs.origin_.x) * (px - obs.origin_.x) + (py - obs.origin_.y) * (py - obs.origin_.y)
386  + (pz - obs.origin_.z) * (pz - obs.origin_.z);
387 
388  // if the point is far enough away... we won't consider it
389  if (sq_dist >= sq_obstacle_range)
390  {
391  ROS_DEBUG("The point is too far away");
392  continue;
393  }
394 
395  // now we need to compute the map coordinates for the observation
396  unsigned int mx, my;
397  if (!worldToMap(px, py, mx, my))
398  {
399  ROS_DEBUG("Computing map coords failed");
400  continue;
401  }
402 
403  unsigned int index = getIndex(mx, my);
404  costmap_[index] = LETHAL_OBSTACLE;
405  touch(px, py, min_x, min_y, max_x, max_y);
406  }
407  }
408 
409  updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
410 }
411 
412 void ObstacleLayer::updateFootprint(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,
413  double* max_x, double* max_y)
414 {
415  if (!footprint_clearing_enabled_) return;
416  transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_);
417 
418  for (unsigned int i = 0; i < transformed_footprint_.size(); i++)
419  {
420  touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
421  }
422 }
423 
424 void ObstacleLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j)
425 {
426  if (!enabled_)
427  return;
428 
430  {
432  }
433 
434  switch (combination_method_)
435  {
436  case 0: // Overwrite
437  updateWithOverwrite(master_grid, min_i, min_j, max_i, max_j);
438  break;
439  case 1: // Maximum
440  updateWithMax(master_grid, min_i, min_j, max_i, max_j);
441  break;
442  default: // Nothing
443  break;
444  }
445 }
446 
447 void ObstacleLayer::addStaticObservation(costmap_2d::Observation& obs, bool marking, bool clearing)
448 {
449  if (marking)
450  static_marking_observations_.push_back(obs);
451  if (clearing)
452  static_clearing_observations_.push_back(obs);
453 }
454 
455 void ObstacleLayer::clearStaticObservations(bool marking, bool clearing)
456 {
457  if (marking)
459  if (clearing)
461 }
462 
463 bool ObstacleLayer::getMarkingObservations(std::vector<Observation>& marking_observations) const
464 {
465  bool current = true;
466  // get the marking observations
467  for (unsigned int i = 0; i < marking_buffers_.size(); ++i)
468  {
469  marking_buffers_[i]->lock();
470  marking_buffers_[i]->getObservations(marking_observations);
471  current = marking_buffers_[i]->isCurrent() && current;
472  marking_buffers_[i]->unlock();
473  }
474  marking_observations.insert(marking_observations.end(),
476  return current;
477 }
478 
479 bool ObstacleLayer::getClearingObservations(std::vector<Observation>& clearing_observations) const
480 {
481  bool current = true;
482  // get the clearing observations
483  for (unsigned int i = 0; i < clearing_buffers_.size(); ++i)
484  {
485  clearing_buffers_[i]->lock();
486  clearing_buffers_[i]->getObservations(clearing_observations);
487  current = clearing_buffers_[i]->isCurrent() && current;
488  clearing_buffers_[i]->unlock();
489  }
490  clearing_observations.insert(clearing_observations.end(),
492  return current;
493 }
494 
495 void ObstacleLayer::raytraceFreespace(const Observation& clearing_observation, double* min_x, double* min_y,
496  double* max_x, double* max_y)
497 {
498  double ox = clearing_observation.origin_.x;
499  double oy = clearing_observation.origin_.y;
500  const sensor_msgs::PointCloud2 &cloud = *(clearing_observation.cloud_);
501 
502  // get the map coordinates of the origin of the sensor
503  unsigned int x0, y0;
504  if (!worldToMap(ox, oy, x0, y0))
505  {
507  1.0, "The origin for the sensor at (%.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
508  ox, oy);
509  return;
510  }
511 
512  // we can pre-compute the enpoints of the map outside of the inner loop... we'll need these later
513  double origin_x = origin_x_, origin_y = origin_y_;
514  double map_end_x = origin_x + size_x_ * resolution_;
515  double map_end_y = origin_y + size_y_ * resolution_;
516 
517 
518  touch(ox, oy, min_x, min_y, max_x, max_y);
519 
520  // for each point in the cloud, we want to trace a line from the origin and clear obstacles along it
523 
524  for (; iter_x != iter_x.end(); ++iter_x, ++iter_y)
525  {
526  double wx = *iter_x;
527  double wy = *iter_y;
528 
529  // now we also need to make sure that the enpoint we're raytracing
530  // to isn't off the costmap and scale if necessary
531  double a = wx - ox;
532  double b = wy - oy;
533 
534  // the minimum value to raytrace from is the origin
535  if (wx < origin_x)
536  {
537  double t = (origin_x - ox) / a;
538  wx = origin_x;
539  wy = oy + b * t;
540  }
541  if (wy < origin_y)
542  {
543  double t = (origin_y - oy) / b;
544  wx = ox + a * t;
545  wy = origin_y;
546  }
547 
548  // the maximum value to raytrace to is the end of the map
549  if (wx > map_end_x)
550  {
551  double t = (map_end_x - ox) / a;
552  wx = map_end_x - .001;
553  wy = oy + b * t;
554  }
555  if (wy > map_end_y)
556  {
557  double t = (map_end_y - oy) / b;
558  wx = ox + a * t;
559  wy = map_end_y - .001;
560  }
561 
562  // now that the vector is scaled correctly... we'll get the map coordinates of its endpoint
563  unsigned int x1, y1;
564 
565  // check for legality just in case
566  if (!worldToMap(wx, wy, x1, y1))
567  continue;
568 
569  unsigned int cell_raytrace_range = cellDistance(clearing_observation.raytrace_range_);
570  MarkCell marker(costmap_, FREE_SPACE);
571  // and finally... we can execute our trace to clear obstacles along that line
572  raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_range);
573 
574  updateRaytraceBounds(ox, oy, wx, wy, clearing_observation.raytrace_range_, min_x, min_y, max_x, max_y);
575  }
576 }
577 
579 {
580  // if we're stopped we need to re-subscribe to topics
581  for (unsigned int i = 0; i < observation_subscribers_.size(); ++i)
582  {
583  if (observation_subscribers_[i] != NULL)
584  observation_subscribers_[i]->subscribe();
585  }
586 
587  for (unsigned int i = 0; i < observation_buffers_.size(); ++i)
588  {
589  if (observation_buffers_[i])
590  observation_buffers_[i]->resetLastUpdated();
591  }
592 }
594 {
595  for (unsigned int i = 0; i < observation_subscribers_.size(); ++i)
596  {
597  if (observation_subscribers_[i] != NULL)
598  observation_subscribers_[i]->unsubscribe();
599  }
600 }
601 
602 void ObstacleLayer::updateRaytraceBounds(double ox, double oy, double wx, double wy, double range,
603  double* min_x, double* min_y, double* max_x, double* max_y)
604 {
605  double dx = wx-ox, dy = wy-oy;
606  double full_distance = hypot(dx, dy);
607  double scale = std::min(1.0, range / full_distance);
608  double ex = ox + dx * scale, ey = oy + dy * scale;
609  touch(ex, ey, min_x, min_y, max_x, max_y);
610 }
611 
613 {
614  deactivate();
615  resetMaps();
616  current_ = true;
617  activate();
618 }
619 
620 } // namespace costmap_2d
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
Definition: costmap_2d.cpp:440
void projectLaser(const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default)
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_...
geometry_msgs::Point origin_
Definition: observation.h:96
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
LayeredCostmap * layered_costmap_
Definition: layer.h:121
bool getMarkingObservations(std::vector< costmap_2d::Observation > &marking_observations) const
Get the observations used to mark space.
#define ROS_FATAL(...)
void updateWithOverwrite(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
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().
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
Definition: costmap_2d.cpp:181
unsigned int size_y_
Definition: costmap_2d.h:422
virtual void deactivate()
Stop publishers.
std::vector< costmap_2d::Observation > static_clearing_observations_
void clearStaticObservations(bool marking, bool clearing)
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > marking_buffers_
Used to store observation buffers used for marking obstacles.
std::vector< geometry_msgs::Point > transformed_footprint_
std::string getGlobalFrameID() const
void updateRaytraceBounds(double ox, double oy, double wx, double wy, double range, double *min_x, double *min_y, double *max_x, double *max_y)
std::vector< costmap_2d::Observation > static_marking_observations_
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition: costmap_2d.h:171
INLINE Rall1d< T, V, S > hypot(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
laser_geometry::LaserProjection projector_
Used to project laser scans into point clouds.
void reconfigureCB(costmap_2d::ObstaclePluginConfig &config, uint32_t level)
Stores an observation in terms of a point cloud and the origin of the source.
Definition: observation.h:46
unsigned int size_x_
Definition: costmap_2d.h:421
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...
static const unsigned char FREE_SPACE
Definition: cost_values.h:45
#define ROS_WARN(...)
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
Definition: costmap_2d.cpp:445
geometry_msgs::TransformStamped t
void addStaticObservation(costmap_2d::Observation &obs, bool marking, bool clearing)
void useExtraBounds(double *min_x, double *min_y, double *max_x, double *max_y)
std::string name_
Definition: layer.h:124
std::vector< boost::shared_ptr< tf2_ros::MessageFilterBase > > observation_notifiers_
Used to make sure that transforms are available for each sensor.
const std::vector< geometry_msgs::Point > & getFootprint() const
Convenience function for layered_costmap_->getFootprint().
Definition: layer.cpp:51
tf2_ros::Buffer * tf_
Definition: layer.h:125
double max_obstacle_height_
Max Obstacle Height.
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:360
bool param(const std::string &param_name, T &param_val, const T &default_val) const
virtual void activate()
Restart publishers if they&#39;ve been stopped.
Takes in point clouds from sensors, transforms them to the desired frame, and stores them...
#define ROS_WARN_THROTTLE(period,...)
#define ROS_INFO(...)
bool getParam(const std::string &key, std::string &s) const
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
Definition: costmap_2d.cpp:87
std::vector< boost::shared_ptr< message_filters::SubscriberBase > > observation_subscribers_
Used for the observation message filters.
double epsilon
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
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:315
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
dynamic_reconfigure::Server< costmap_2d::ObstaclePluginConfig > * dsrv_
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.
unsigned char default_value_
Definition: costmap_2d.h:427
bool searchParam(const std::string &key, std::string &result) const
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > clearing_buffers_
Used to store observation buffers used for clearing obstacles.
bool enabled_
Currently this var is managed by subclasses. TODO: make this managed by this class and/or container c...
Definition: layer.h:123
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization...
sensor_msgs::PointCloud2 * cloud_
Definition: observation.h:97
static bool convertPointCloudToPointCloud2(const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)
static const unsigned char LETHAL_OBSTACLE
Definition: cost_values.h:43
static const unsigned char NO_INFORMATION
Definition: cost_values.h:42
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:208
void pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering PointCloud2 messages.
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:260
void updateWithMax(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.h:60
void transformLaserScanToPointCloud(const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, tf::Transformer &tf, double range_cutoff, int channel_options=channel_option::Default)
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
unsigned char * costmap_
Definition: costmap_2d.h:426
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
void laserScanCallback(const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering LaserScan messages.
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > observation_buffers_
Used to store observations from various sensors.
bool getClearingObservations(std::vector< costmap_2d::Observation > &clearing_observations) const
Get the observations used to clear space.
std::string global_frame_
The global frame for the costmap.
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
void pointCloudCallback(const sensor_msgs::PointCloudConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering PointCloud messages.
#define ROS_DEBUG(...)


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Wed Jun 22 2022 02:07:03