costmap_2d_ros.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 <cstdio>
41 #include <string>
42 #include <algorithm>
43 #include <vector>
44 #include <tf2/convert.h>
45 #include <tf2/utils.h>
47 
48 using namespace std;
49 
50 namespace costmap_2d
51 {
52 
53 void move_parameter(ros::NodeHandle& old_h, ros::NodeHandle& new_h, std::string name, bool should_delete = true)
54 {
55  if (!old_h.hasParam(name))
56  return;
57 
58  XmlRpc::XmlRpcValue value;
59  old_h.getParam(name, value);
60  new_h.setParam(name, value);
61  if (should_delete) old_h.deleteParam(name);
62 }
63 
64 Costmap2DROS::Costmap2DROS(const std::string& name, tf2_ros::Buffer& tf) :
65  layered_costmap_(NULL),
66  name_(name),
67  tf_(tf),
68  transform_tolerance_(0.3),
69  map_update_thread_shutdown_(false),
70  stop_updates_(false),
71  initialized_(true),
72  stopped_(false),
73  map_update_thread_(NULL),
74  last_publish_(0),
75  plugin_loader_("costmap_2d", "costmap_2d::Layer"),
76  publisher_(NULL),
77  dsrv_(NULL),
78  footprint_padding_(0.0)
79 {
80 
81  ros::NodeHandle private_nh("~/" + name);
82  ros::NodeHandle g_nh;
83 
84  // get global and robot base frame names
85  private_nh.param("global_frame", global_frame_, std::string("map"));
86  private_nh.param("robot_base_frame", robot_base_frame_, std::string("base_link"));
87 
88  ros::Time last_error = ros::Time::now();
89  std::string tf_error;
90  // we need to make sure that the transform between the robot base frame and the global frame is available
91  while (ros::ok()
93  {
94  ros::spinOnce();
95  if (last_error + ros::Duration(5.0) < ros::Time::now())
96  {
97  ROS_WARN("Timed out waiting for transform from %s to %s to become available before running costmap, tf error: %s",
98  robot_base_frame_.c_str(), global_frame_.c_str(), tf_error.c_str());
99  last_error = ros::Time::now();
100  }
101  // The error string will accumulate and errors will typically be the same, so the last
102  // will do for the warning above. Reset the string here to avoid accumulation.
103  tf_error.clear();
104  }
105 
106  // check if we want a rolling window version of the costmap
107  bool rolling_window, track_unknown_space, always_send_full_costmap;
108  private_nh.param("rolling_window", rolling_window, false);
109  private_nh.param("track_unknown_space", track_unknown_space, false);
110  private_nh.param("always_send_full_costmap", always_send_full_costmap, false);
111 
112  layered_costmap_ = new LayeredCostmap(global_frame_, rolling_window, track_unknown_space);
113 
114  if (!private_nh.hasParam("plugins"))
115  {
116  loadOldParameters(private_nh);
117  } else {
118  warnForOldParameters(private_nh);
119  }
120 
121  if (private_nh.hasParam("plugins"))
122  {
123  XmlRpc::XmlRpcValue my_list;
124  private_nh.getParam("plugins", my_list);
125  for (int32_t i = 0; i < my_list.size(); ++i)
126  {
127  std::string pname = static_cast<std::string>(my_list[i]["name"]);
128  std::string type = static_cast<std::string>(my_list[i]["type"]);
129  ROS_INFO("%s: Using plugin \"%s\"", name_.c_str(), pname.c_str());
130 
131  copyParentParameters(pname, type, private_nh);
132 
133  boost::shared_ptr<Layer> plugin = plugin_loader_.createInstance(type);
134  layered_costmap_->addPlugin(plugin);
135  plugin->initialize(layered_costmap_, name + "/" + pname, &tf_);
136  }
137  }
138 
139  // subscribe to the footprint topic
140  std::string topic_param, topic;
141  if (!private_nh.searchParam("footprint_topic", topic_param))
142  {
143  topic_param = "footprint_topic";
144  }
145 
146  private_nh.param(topic_param, topic, std::string("footprint"));
148 
149  if (!private_nh.searchParam("published_footprint_topic", topic_param))
150  {
151  topic_param = "published_footprint";
152  }
153 
154  private_nh.param(topic_param, topic, std::string("footprint")); // TODO: revert to oriented_footprint in N-turtle
155  footprint_pub_ = private_nh.advertise<geometry_msgs::PolygonStamped>(topic, 1);
156 
158 
159  publisher_ = new Costmap2DPublisher(&private_nh, layered_costmap_->getCostmap(), global_frame_, "costmap",
160  always_send_full_costmap);
161 
162  // create a thread to handle updating the map
163  stop_updates_ = false;
164  initialized_ = true;
165  stopped_ = false;
166 
167  dsrv_ = new dynamic_reconfigure::Server<Costmap2DConfig>(ros::NodeHandle("~/" + name));
168  dynamic_reconfigure::Server<Costmap2DConfig>::CallbackType cb = [this](auto& config, auto level){ reconfigureCB(config, level); };
169  dsrv_->setCallback(cb);
170 }
171 
172 void Costmap2DROS::setUnpaddedRobotFootprintPolygon(const geometry_msgs::Polygon& footprint)
173 {
175 }
176 
178 {
180  if (map_update_thread_ != NULL)
181  {
182  map_update_thread_->join();
183  delete map_update_thread_;
184  }
185  if (publisher_ != NULL)
186  delete publisher_;
187 
188  delete layered_costmap_;
189  delete dsrv_;
190 }
191 
193 {
194  ROS_WARN("%s: Parameter \"plugins\" not provided, loading pre-Hydro parameters", name_.c_str());
195  bool flag;
196  std::string s;
197  std::vector < XmlRpc::XmlRpcValue > plugins;
198 
200  SuperValue super_map;
201  SuperValue super_array;
202 
203  if (nh.getParam("static_map", flag) && flag)
204  {
205  map["name"] = XmlRpc::XmlRpcValue("static_layer");
206  map["type"] = XmlRpc::XmlRpcValue("costmap_2d::StaticLayer");
207  super_map.setStruct(&map);
208  plugins.push_back(super_map);
209 
210  ros::NodeHandle map_layer(nh, "static_layer");
211  move_parameter(nh, map_layer, "map_topic");
212  move_parameter(nh, map_layer, "unknown_cost_value");
213  move_parameter(nh, map_layer, "lethal_cost_threshold");
214  move_parameter(nh, map_layer, "track_unknown_space", false);
215  }
216 
217  ros::NodeHandle obstacles(nh, "obstacle_layer");
218  if (nh.getParam("map_type", s) && s == "voxel")
219  {
220  map["name"] = XmlRpc::XmlRpcValue("obstacle_layer");
221  map["type"] = XmlRpc::XmlRpcValue("costmap_2d::VoxelLayer");
222  super_map.setStruct(&map);
223  plugins.push_back(super_map);
224 
225  move_parameter(nh, obstacles, "origin_z");
226  move_parameter(nh, obstacles, "z_resolution");
227  move_parameter(nh, obstacles, "z_voxels");
228  move_parameter(nh, obstacles, "mark_threshold");
229  move_parameter(nh, obstacles, "unknown_threshold");
230  move_parameter(nh, obstacles, "publish_voxel_map");
231  }
232  else
233  {
234  map["name"] = XmlRpc::XmlRpcValue("obstacle_layer");
235  map["type"] = XmlRpc::XmlRpcValue("costmap_2d::ObstacleLayer");
236  super_map.setStruct(&map);
237  plugins.push_back(super_map);
238  }
239 
240  move_parameter(nh, obstacles, "max_obstacle_height");
241  move_parameter(nh, obstacles, "raytrace_range");
242  move_parameter(nh, obstacles, "obstacle_range");
243  move_parameter(nh, obstacles, "track_unknown_space", true);
244  nh.param("observation_sources", s, std::string(""));
245  std::stringstream ss(s);
246  std::string source;
247  while (ss >> source)
248  {
249  move_parameter(nh, obstacles, source);
250  }
251  move_parameter(nh, obstacles, "observation_sources");
252 
253  ros::NodeHandle inflation(nh, "inflation_layer");
254  move_parameter(nh, inflation, "cost_scaling_factor");
255  move_parameter(nh, inflation, "inflation_radius");
256  map["name"] = XmlRpc::XmlRpcValue("inflation_layer");
257  map["type"] = XmlRpc::XmlRpcValue("costmap_2d::InflationLayer");
258  super_map.setStruct(&map);
259  plugins.push_back(super_map);
260 
261  super_array.setArray(&plugins);
262  nh.setParam("plugins", super_array);
263 }
264 
265 void Costmap2DROS::copyParentParameters(const std::string& plugin_name, const std::string& plugin_type, ros::NodeHandle& nh)
266 {
267  ros::NodeHandle target_layer(nh, plugin_name);
268 
269  if(plugin_type == "costmap_2d::StaticLayer")
270  {
271  move_parameter(nh, target_layer, "map_topic", false);
272  move_parameter(nh, target_layer, "unknown_cost_value", false);
273  move_parameter(nh, target_layer, "lethal_cost_threshold", false);
274  move_parameter(nh, target_layer, "track_unknown_space", false);
275  }
276  else if(plugin_type == "costmap_2d::VoxelLayer")
277  {
278  move_parameter(nh, target_layer, "origin_z", false);
279  move_parameter(nh, target_layer, "z_resolution", false);
280  move_parameter(nh, target_layer, "z_voxels", false);
281  move_parameter(nh, target_layer, "mark_threshold", false);
282  move_parameter(nh, target_layer, "unknown_threshold", false);
283  move_parameter(nh, target_layer, "publish_voxel_map", false);
284  }
285  else if(plugin_type == "costmap_2d::ObstacleLayer")
286  {
287  move_parameter(nh, target_layer, "max_obstacle_height", false);
288  move_parameter(nh, target_layer, "raytrace_range", false);
289  move_parameter(nh, target_layer, "obstacle_range", false);
290  move_parameter(nh, target_layer, "track_unknown_space", false);
291  }
292  else if(plugin_type == "costmap_2d::InflationLayer")
293  {
294  move_parameter(nh, target_layer, "cost_scaling_factor", false);
295  move_parameter(nh, target_layer, "inflation_radius", false);
296  }
297 }
298 
300 {
301  checkOldParam(nh, "static_map");
302  checkOldParam(nh, "map_type");
303 }
304 
305 void Costmap2DROS::checkOldParam(ros::NodeHandle& nh, const std::string &param_name){
306  if(nh.hasParam(param_name)){
307  ROS_WARN("%s: Pre-Hydro parameter \"%s\" unused since \"plugins\" is provided", name_.c_str(), param_name.c_str());
308  }
309 }
310 
311 void Costmap2DROS::reconfigureCB(costmap_2d::Costmap2DConfig &config, uint32_t level)
312 {
313  transform_tolerance_ = config.transform_tolerance;
314  if (map_update_thread_ != NULL)
315  {
317  map_update_thread_->join();
318  delete map_update_thread_;
319  map_update_thread_ = NULL;
320  }
322  double map_update_frequency = config.update_frequency;
323 
324  double map_publish_frequency = config.publish_frequency;
325  if (map_publish_frequency > 0)
326  publish_cycle = ros::Duration(1 / map_publish_frequency);
327  else
329 
330  // find size parameters
331  double map_width_meters = config.width, map_height_meters = config.height, resolution = config.resolution, origin_x =
332  config.origin_x,
333  origin_y = config.origin_y;
334 
336  {
337  layered_costmap_->resizeMap((unsigned int)(map_width_meters / resolution),
338  (unsigned int)(map_height_meters / resolution), resolution, origin_x, origin_y);
339  }
340 
341  // If the padding has changed, call setUnpaddedRobotFootprint() to
342  // re-apply the padding.
343  if (footprint_padding_ != config.footprint_padding)
344  {
345  footprint_padding_ = config.footprint_padding;
347  }
348 
350 
351  old_config_ = config;
352 
353  // only construct the thread if the frequency is positive
354  if(map_update_frequency > 0.0)
355  map_update_thread_ = new boost::thread(boost::bind(&Costmap2DROS::mapUpdateLoop, this, map_update_frequency));
356 }
357 
358 void Costmap2DROS::readFootprintFromConfig(const costmap_2d::Costmap2DConfig &new_config,
359  const costmap_2d::Costmap2DConfig &old_config)
360 {
361  // Only change the footprint if footprint or robot_radius has
362  // changed. Otherwise we might overwrite a footprint sent on a
363  // topic by a dynamic_reconfigure call which was setting some other
364  // variable.
365  if (new_config.footprint == old_config.footprint &&
366  new_config.robot_radius == old_config.robot_radius)
367  {
368  return;
369  }
370 
371  if (new_config.footprint != "" && new_config.footprint != "[]")
372  {
373  std::vector<geometry_msgs::Point> new_footprint;
374  if (makeFootprintFromString(new_config.footprint, new_footprint))
375  {
376  setUnpaddedRobotFootprint(new_footprint);
377  }
378  else
379  {
380  ROS_ERROR("Invalid footprint string from dynamic reconfigure");
381  }
382  }
383  else
384  {
385  // robot_radius may be 0, but that must be intended at this point.
386  setUnpaddedRobotFootprint(makeFootprintFromRadius(new_config.robot_radius));
387  }
388 }
389 
390 void Costmap2DROS::setUnpaddedRobotFootprint(const std::vector<geometry_msgs::Point>& points)
391 {
392  unpadded_footprint_ = points;
393  padded_footprint_ = points;
395 
397 }
398 
400 {
401  // don't allow configuration to happen while this check occurs
402  // boost::recursive_mutex::scoped_lock mcl(configuration_mutex_);
403 
404  geometry_msgs::PoseStamped new_pose;
405 
406  if (!getRobotPose(new_pose))
407  {
408  ROS_WARN_THROTTLE(1.0, "Could not get robot pose, cancelling reconfiguration");
409  }
410 }
411 
412 void Costmap2DROS::mapUpdateLoop(double frequency)
413 {
414  ros::NodeHandle nh;
415  ros::Rate r(frequency);
416  while (nh.ok() && !map_update_thread_shutdown_)
417  {
418  #ifdef HAVE_SYS_TIME_H
419  struct timeval start, end;
420  double start_t, end_t, t_diff;
421  gettimeofday(&start, NULL);
422  #endif
423 
424  updateMap();
425 
426  #ifdef HAVE_SYS_TIME_H
427  gettimeofday(&end, NULL);
428  start_t = start.tv_sec + double(start.tv_usec) / 1e6;
429  end_t = end.tv_sec + double(end.tv_usec) / 1e6;
430  t_diff = end_t - start_t;
431  ROS_DEBUG("Map update time: %.9f", t_diff);
432  #endif
433 
435  {
436  unsigned int x0, y0, xn, yn;
437  layered_costmap_->getBounds(&x0, &xn, &y0, &yn);
438  publisher_->updateBounds(x0, xn, y0, yn);
439 
440  ros::Time now = ros::Time::now();
441  if (last_publish_ + publish_cycle < now)
442  {
444  last_publish_ = now;
445  }
446  }
447  r.sleep();
448  // make sure to sleep for the remainder of our cycle time
449  if (r.cycleTime() > ros::Duration(1 / frequency))
450  ROS_WARN("Map update loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", frequency,
451  r.cycleTime().toSec());
452  }
453 }
454 
456 {
457  if (!stop_updates_)
458  {
459  // get global pose
460  geometry_msgs::PoseStamped pose;
461  if (getRobotPose (pose))
462  {
463  double x = pose.pose.position.x,
464  y = pose.pose.position.y,
465  yaw = tf2::getYaw(pose.pose.orientation);
466 
467  layered_costmap_->updateMap(x, y, yaw);
468 
469  geometry_msgs::PolygonStamped footprint;
470  footprint.header.frame_id = global_frame_;
471  footprint.header.stamp = ros::Time::now();
472  transformFootprint(x, y, yaw, padded_footprint_, footprint);
473  footprint_pub_.publish(footprint);
474 
475  initialized_ = true;
476  }
477  }
478 }
479 
481 {
482  std::vector < boost::shared_ptr<Layer> > *plugins = layered_costmap_->getPlugins();
483  // check if we're stopped or just paused
484  if (stopped_)
485  {
486  // if we're stopped we need to re-subscribe to topics
487  for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins->begin(); plugin != plugins->end();
488  ++plugin)
489  {
490  (*plugin)->activate();
491  }
492  stopped_ = false;
493  }
494  stop_updates_ = false;
495 
496  // block until the costmap is re-initialized.. meaning one update cycle has run
497  // note: this does not hold, if the user has disabled map-updates allgother
498  ros::Rate r(100.0);
499  while (ros::ok() && !initialized_ && map_update_thread_)
500  r.sleep();
501 }
502 
504 {
505  stop_updates_ = true;
506  std::vector < boost::shared_ptr<Layer> > *plugins = layered_costmap_->getPlugins();
507  // unsubscribe from topics
508  for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins->begin(); plugin != plugins->end();
509  ++plugin)
510  {
511  (*plugin)->deactivate();
512  }
513  initialized_ = false;
514  stopped_ = true;
515 }
516 
518 {
519  stop_updates_ = true;
520  initialized_ = false;
521 }
522 
524 {
525  stop_updates_ = false;
526 
527  // block until the costmap is re-initialized.. meaning one update cycle has run
528  ros::Rate r(100.0);
529  while (!initialized_)
530  r.sleep();
531 }
532 
533 
535 {
537  top->resetMap(0, 0, top->getSizeInCellsX(), top->getSizeInCellsY());
538  std::vector < boost::shared_ptr<Layer> > *plugins = layered_costmap_->getPlugins();
539  for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins->begin(); plugin != plugins->end();
540  ++plugin)
541  {
542  (*plugin)->reset();
543  }
544 }
545 
546 bool Costmap2DROS::getRobotPose(geometry_msgs::PoseStamped& global_pose) const
547 {
548  tf2::toMsg(tf2::Transform::getIdentity(), global_pose.pose);
549  geometry_msgs::PoseStamped robot_pose;
550  tf2::toMsg(tf2::Transform::getIdentity(), robot_pose.pose);
551  robot_pose.header.frame_id = robot_base_frame_;
552  robot_pose.header.stamp = ros::Time();
553  ros::Time current_time = ros::Time::now(); // save time for checking tf delay later
554 
555  // get the global pose of the robot
556  try
557  {
558  // use current time if possible (makes sure it's not in the future)
559  if (tf_.canTransform(global_frame_, robot_base_frame_, current_time))
560  {
561  geometry_msgs::TransformStamped transform = tf_.lookupTransform(global_frame_, robot_base_frame_, current_time);
562  tf2::doTransform(robot_pose, global_pose, transform);
563  }
564  // use the latest otherwise
565  else
566  {
567  tf_.transform(robot_pose, global_pose, global_frame_);
568  }
569  }
570  catch (tf2::LookupException& ex)
571  {
572  ROS_ERROR_THROTTLE(1.0, "No Transform available Error looking up robot pose: %s\n", ex.what());
573  return false;
574  }
575  catch (tf2::ConnectivityException& ex)
576  {
577  ROS_ERROR_THROTTLE(1.0, "Connectivity Error looking up robot pose: %s\n", ex.what());
578  return false;
579  }
580  catch (tf2::ExtrapolationException& ex)
581  {
582  ROS_ERROR_THROTTLE(1.0, "Extrapolation Error looking up robot pose: %s\n", ex.what());
583  return false;
584  }
585  // check global_pose timeout
586  if (!global_pose.header.stamp.isZero() && current_time.toSec() - global_pose.header.stamp.toSec() > transform_tolerance_)
587  {
588  ROS_WARN_THROTTLE(1.0,
589  "Costmap2DROS transform timeout. Current time: %.4f, global_pose stamp: %.4f, tolerance: %.4f",
590  current_time.toSec(), global_pose.header.stamp.toSec(), transform_tolerance_);
591  return false;
592  }
593 
594  return true;
595 }
596 
597 void Costmap2DROS::getOrientedFootprint(std::vector<geometry_msgs::Point>& oriented_footprint) const
598 {
599  geometry_msgs::PoseStamped global_pose;
600  if (!getRobotPose(global_pose))
601  return;
602 
603  double yaw = tf2::getYaw(global_pose.pose.orientation);
604  transformFootprint(global_pose.pose.position.x, global_pose.pose.position.y, yaw,
605  padded_footprint_, oriented_footprint);
606 }
607 
608 } // namespace costmap_2d
XmlRpc::XmlRpcValue::size
int size() const
ROS_ERROR_THROTTLE
#define ROS_ERROR_THROTTLE(period,...)
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
costmap_2d::LayeredCostmap::isSizeLocked
bool isSizeLocked()
Definition: layered_costmap.h:153
costmap_2d::Costmap2DROS::old_config_
costmap_2d::Costmap2DConfig old_config_
Definition: costmap_2d_ros.h:277
costmap_2d::padFootprint
void padFootprint(std::vector< geometry_msgs::Point > &footprint, double padding)
Adds the specified amount of padding to the footprint (in place)
Definition: footprint.cpp:138
boost::shared_ptr
costmap_2d::toPointVector
std::vector< geometry_msgs::Point > toPointVector(geometry_msgs::Polygon polygon)
Convert Polygon msg to vector of Points.
Definition: footprint.cpp:96
costmap_2d::Costmap2DROS::tf_
tf2_ros::Buffer & tf_
Used for transforming point clouds.
Definition: costmap_2d_ros.h:241
XmlRpc::XmlRpcValue::ValueStruct
std::map< std::string, XmlRpcValue > ValueStruct
tf2::getYaw
double getYaw(const A &a)
utils.h
costmap_2d::Costmap2DROS::readFootprintFromConfig
void readFootprintFromConfig(const costmap_2d::Costmap2DConfig &new_config, const costmap_2d::Costmap2DConfig &old_config)
Set the footprint from the new_config object.
Definition: costmap_2d_ros.cpp:358
s
XmlRpcServer s
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
costmap_2d::Costmap2DROS::setUnpaddedRobotFootprintPolygon
void setUnpaddedRobotFootprintPolygon(const geometry_msgs::Polygon &footprint)
Set the footprint of the robot to be the given polygon, padded by footprint_padding.
Definition: costmap_2d_ros.cpp:172
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
costmap_2d::LayeredCostmap::setFootprint
void setFootprint(const std::vector< geometry_msgs::Point > &footprint_spec)
Updates the stored footprint, updates the circumscribed and inscribed radii, and calls onFootprintCha...
Definition: layered_costmap.cpp:177
costmap_2d::Costmap2DROS::~Costmap2DROS
~Costmap2DROS()
Definition: costmap_2d_ros.cpp:177
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
costmap_2d::LayeredCostmap::resizeMap
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
Definition: layered_costmap.cpp:82
layered_costmap.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
ros::NodeHandle::deleteParam
bool deleteParam(const std::string &key) const
costmap_2d::makeFootprintFromParams
std::vector< geometry_msgs::Point > makeFootprintFromParams(ros::NodeHandle &nh)
Read the ros-params "footprint" and/or "robot_radius" from the given NodeHandle using searchParam() t...
Definition: footprint.cpp:212
costmap_2d::Costmap2DROS::movementCB
void movementCB(const ros::TimerEvent &event)
Definition: costmap_2d_ros.cpp:399
TimeBase< Time, Duration >::toSec
double toSec() const
costmap_2d::Costmap2DROS::loadOldParameters
void loadOldParameters(ros::NodeHandle &nh)
Definition: costmap_2d_ros.cpp:192
costmap_2d::Costmap2DROS::resume
void resume()
Resumes costmap updates.
Definition: costmap_2d_ros.cpp:523
SuperValue::setArray
void setArray(XmlRpc::XmlRpcValue::ValueArray *a)
Definition: costmap_2d_ros.h:97
costmap_2d::Costmap2D
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.h:96
costmap_2d::Costmap2DROS::checkOldParam
void checkOldParam(ros::NodeHandle &nh, const std::string &param_name)
Definition: costmap_2d_ros.cpp:305
SuperValue::setStruct
void setStruct(XmlRpc::XmlRpcValue::ValueStruct *a)
Definition: costmap_2d_ros.h:92
costmap_2d::Costmap2DROS::transform_tolerance_
double transform_tolerance_
timeout before transform errors
Definition: costmap_2d_ros.h:244
costmap_2d::Costmap2DPublisher::publishCostmap
void publishCostmap()
Publishes the visualization data over ROS.
Definition: costmap_2d_publisher.cpp:156
costmap_2d::Costmap2DROS::map_update_thread_
boost::thread * map_update_thread_
A thread for updating the map.
Definition: costmap_2d_ros.h:263
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
costmap_2d::Costmap2DROS::robot_base_frame_
std::string robot_base_frame_
The frame_id of the robot base.
Definition: costmap_2d_ros.h:243
costmap_2d::Costmap2DROS::mapUpdateLoop
void mapUpdateLoop(double frequency)
Definition: costmap_2d_ros.cpp:412
costmap_2d::Costmap2DROS::footprint_pub_
ros::Publisher footprint_pub_
Definition: costmap_2d_ros.h:273
tf2_ros::Buffer::canTransform
virtual bool canTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout, std::string *errstr=NULL) const
costmap_2d::LayeredCostmap::getBounds
void getBounds(unsigned int *x0, unsigned int *xn, unsigned int *y0, unsigned int *yn)
Definition: layered_costmap.h:158
costmap_2d::Costmap2DROS::unpadded_footprint_
std::vector< geometry_msgs::Point > unpadded_footprint_
Definition: costmap_2d_ros.h:274
costmap_2d::Costmap2DROS::resetLayers
void resetLayers()
Reset each individual layer.
Definition: costmap_2d_ros.cpp:534
costmap_2d::LayeredCostmap::getPlugins
std::vector< boost::shared_ptr< Layer > > * getPlugins()
Definition: layered_costmap.h:143
tf2::Transform::getIdentity
static const Transform & getIdentity()
ROS_DEBUG
#define ROS_DEBUG(...)
costmap_2d::Costmap2DROS::global_frame_
std::string global_frame_
The global frame for the costmap.
Definition: costmap_2d_ros.h:242
tf2::ExtrapolationException
costmap_2d::Costmap2DROS::dsrv_
dynamic_reconfigure::Server< costmap_2d::Costmap2DConfig > * dsrv_
Definition: costmap_2d_ros.h:268
costmap_2d::Costmap2DROS::name_
std::string name_
Definition: costmap_2d_ros.h:240
costmap_2d::Costmap2DROS::footprint_sub_
ros::Subscriber footprint_sub_
Definition: costmap_2d_ros.h:272
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
costmap_2d::Costmap2DROS::plugin_loader_
pluginlib::ClassLoader< Layer > plugin_loader_
Definition: costmap_2d_ros.h:266
costmap_2d::Costmap2DROS::getOrientedFootprint
void getOrientedFootprint(std::vector< geometry_msgs::Point > &oriented_footprint) const
Build the oriented footprint of the robot at the robot's current pose.
Definition: costmap_2d_ros.cpp:597
costmap_2d::Costmap2D::getSizeInCellsY
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:435
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
costmap_2d::makeFootprintFromString
bool makeFootprintFromString(const std::string &footprint_string, std::vector< geometry_msgs::Point > &footprint)
Make the footprint from the given string.
Definition: footprint.cpp:170
ROS_WARN
#define ROS_WARN(...)
tf2_ros::Buffer
costmap_2d::Costmap2DROS::initialized_
bool initialized_
Definition: costmap_2d_ros.h:262
costmap_2d::Costmap2DROS::reconfigureCB
void reconfigureCB(costmap_2d::Costmap2DConfig &config, uint32_t level)
Definition: costmap_2d_ros.cpp:311
costmap_2d::Costmap2DROS::setUnpaddedRobotFootprint
void setUnpaddedRobotFootprint(const std::vector< geometry_msgs::Point > &points)
Set the footprint of the robot to be the given set of points, padded by footprint_padding.
Definition: costmap_2d_ros.cpp:390
costmap_2d::Costmap2DROS::stopped_
bool stopped_
Definition: costmap_2d_ros.h:262
costmap_2d::Costmap2DROS::stop_updates_
bool stop_updates_
Definition: costmap_2d_ros.h:262
costmap_2d::Costmap2D::resetMap
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
Definition: costmap_2d.cpp:93
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
costmap_2d::LayeredCostmap::addPlugin
void addPlugin(boost::shared_ptr< Layer > plugin)
Definition: layered_costmap.h:148
tf2::LookupException
ros::TimerEvent
costmap_2d::Costmap2DROS::last_publish_
ros::Time last_publish_
Definition: costmap_2d_ros.h:264
ros::Rate::sleep
bool sleep()
tf2::ConnectivityException
costmap_2d::Costmap2DROS::start
void start()
Subscribes to sensor topics if necessary and starts costmap updates, can be called to restart the cos...
Definition: costmap_2d_ros.cpp:480
costmap_2d::Costmap2DROS::warnForOldParameters
void warnForOldParameters(ros::NodeHandle &nh)
Definition: costmap_2d_ros.cpp:299
costmap_2d::makeFootprintFromRadius
std::vector< geometry_msgs::Point > makeFootprintFromRadius(double radius)
Create a circular footprint from a given radius.
Definition: footprint.cpp:150
costmap_2d::Costmap2DROS::publisher_
Costmap2DPublisher * publisher_
Definition: costmap_2d_ros.h:267
ros::NodeHandle::ok
bool ok() const
costmap_2d::move_parameter
void move_parameter(ros::NodeHandle &old_h, ros::NodeHandle &new_h, std::string name, bool should_delete=true)
Definition: costmap_2d_ros.cpp:53
tf2_ros::BufferInterface::transform
B & transform(const A &in, B &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
costmap_2d::Costmap2DPublisher::updateBounds
void updateBounds(unsigned int x0, unsigned int xn, unsigned int y0, unsigned int yn)
Include the given bounds in the changed-rectangle.
Definition: costmap_2d_publisher.h:102
ros::Time
tf2::doTransform
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
ros::Rate::cycleTime
Duration cycleTime() const
costmap_2d::Costmap2DROS::getRobotPose
bool getRobotPose(geometry_msgs::PoseStamped &global_pose) const
Get the pose of the robot in the global frame of the costmap.
Definition: costmap_2d_ros.cpp:546
costmap_2d::Costmap2DROS::footprint_padding_
float footprint_padding_
Definition: costmap_2d_ros.h:276
costmap_2d::Costmap2DROS::pause
void pause()
Stops the costmap from updating, but sensor data still comes in over the wire.
Definition: costmap_2d_ros.cpp:517
std
costmap_2d::Costmap2DROS::publish_cycle
ros::Duration publish_cycle
Definition: costmap_2d_ros.h:265
SuperValue
Definition: costmap_2d_ros.h:53
costmap_2d::Costmap2DROS::stop
void stop()
Stops costmap updates and unsubscribes from sensor topics.
Definition: costmap_2d_ros.cpp:503
ROS_ERROR
#define ROS_ERROR(...)
costmap_2d::LayeredCostmap::updateMap
void updateMap(double robot_x, double robot_y, double robot_yaw)
Update the underlying costmap with new data. If you want to update the map outside of the update loop...
Definition: layered_costmap.cpp:95
costmap_2d::LayeredCostmap::isInitialized
bool isInitialized()
Definition: layered_costmap.h:166
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
tf2_geometry_msgs.h
tf2::toMsg
B toMsg(const A &a)
costmap_2d::LayeredCostmap
Instantiates different layer plugins and aggregates them into one score.
Definition: layered_costmap.h:91
ros::Rate
tf
convert.h
costmap_2d::LayeredCostmap::getCostmap
Costmap2D * getCostmap()
Definition: layered_costmap.h:128
costmap_2d::Costmap2DPublisher
A tool to periodically publish visualization data from a Costmap2D.
Definition: costmap_2d_publisher.h:87
DurationBase< Duration >::toSec
double toSec() const
costmap_2d::Costmap2D::getSizeInCellsX
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:430
costmap_2d::Costmap2DROS::updateMap
void updateMap()
Definition: costmap_2d_ros.cpp:455
costmap_2d::Costmap2DROS::copyParentParameters
void copyParentParameters(const std::string &plugin_name, const std::string &plugin_type, ros::NodeHandle &nh)
Definition: costmap_2d_ros.cpp:265
tf_
tf2_ros::Buffer * tf_
Definition: footprint_tests.cpp:46
ROS_INFO
#define ROS_INFO(...)
costmap_2d::Costmap2DROS::padded_footprint_
std::vector< geometry_msgs::Point > padded_footprint_
Definition: costmap_2d_ros.h:275
costmap_2d
Definition: array_parser.h:37
ros::Duration
costmap_2d::Costmap2DROS::layered_costmap_
LayeredCostmap * layered_costmap_
Definition: costmap_2d_ros.h:239
costmap_2d::Costmap2DROS::map_update_thread_shutdown_
bool map_update_thread_shutdown_
Definition: costmap_2d_ros.h:261
tf2_ros::Buffer::lookupTransform
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
XmlRpc::XmlRpcValue
ros::NodeHandle
ros::Time::now
static Time now()
costmap_2d_ros.h


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17