Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
costmap_2d_ros.cpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 
39 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
40 
41 #include <memory>
42 #include <chrono>
43 #include <string>
44 #include <vector>
45 #include <utility>
46 
47 #include "nav2_costmap_2d/layered_costmap.hpp"
48 #include "nav2_util/execution_timer.hpp"
49 #include "nav2_util/node_utils.hpp"
50 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
51 #include "tf2_ros/create_timer_ros.h"
52 #include "nav2_util/robot_utils.hpp"
53 #include "rcl_interfaces/msg/set_parameters_result.hpp"
54 
55 using namespace std::chrono_literals;
56 using std::placeholders::_1;
57 using rcl_interfaces::msg::ParameterType;
58 
59 namespace nav2_costmap_2d
60 {
61 Costmap2DROS::Costmap2DROS(const std::string & name)
62 : Costmap2DROS(name, "/", name) {}
63 
64 Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options)
65 : nav2_util::LifecycleNode("costmap", "", options),
66  name_("costmap"),
67  default_plugins_{"static_layer", "obstacle_layer", "inflation_layer"},
68  default_types_{
69  "nav2_costmap_2d::StaticLayer",
70  "nav2_costmap_2d::ObstacleLayer",
71  "nav2_costmap_2d::InflationLayer"}
72 {
73  is_lifecycle_follower_ = false;
74 
75  RCLCPP_INFO(get_logger(), "Creating Costmap");
76 
77  declare_parameter("always_send_full_costmap", rclcpp::ParameterValue(false));
78  declare_parameter("footprint_padding", rclcpp::ParameterValue(0.01f));
79  declare_parameter("footprint", rclcpp::ParameterValue(std::string("[]")));
80  declare_parameter("global_frame", rclcpp::ParameterValue(std::string("map")));
81  declare_parameter("height", rclcpp::ParameterValue(5));
82  declare_parameter("width", rclcpp::ParameterValue(5));
83  declare_parameter("lethal_cost_threshold", rclcpp::ParameterValue(100));
84  declare_parameter(
85  "map_topic", rclcpp::ParameterValue(
86  (parent_namespace_ == "/" ? "/" : parent_namespace_ + "/") + std::string("map")));
87  declare_parameter("observation_sources", rclcpp::ParameterValue(std::string("")));
88  declare_parameter("origin_x", rclcpp::ParameterValue(0.0));
89  declare_parameter("origin_y", rclcpp::ParameterValue(0.0));
90  declare_parameter("plugins", rclcpp::ParameterValue(default_plugins_));
91  declare_parameter("filters", rclcpp::ParameterValue(std::vector<std::string>()));
92  declare_parameter("publish_frequency", rclcpp::ParameterValue(1.0));
93  declare_parameter("resolution", rclcpp::ParameterValue(0.1));
94  declare_parameter("robot_base_frame", rclcpp::ParameterValue(std::string("base_link")));
95  declare_parameter("robot_radius", rclcpp::ParameterValue(0.1));
96  declare_parameter("rolling_window", rclcpp::ParameterValue(false));
97  declare_parameter("track_unknown_space", rclcpp::ParameterValue(false));
98  declare_parameter("transform_tolerance", rclcpp::ParameterValue(0.3));
99  declare_parameter("trinary_costmap", rclcpp::ParameterValue(true));
100  declare_parameter("unknown_cost_value", rclcpp::ParameterValue(static_cast<unsigned char>(0xff)));
101  declare_parameter("update_frequency", rclcpp::ParameterValue(5.0));
102  declare_parameter("use_maximum", rclcpp::ParameterValue(false));
103 }
104 
106  const std::string & name,
107  const std::string & parent_namespace,
108  const std::string & local_namespace)
109 : nav2_util::LifecycleNode(name, "",
110  // NodeOption arguments take precedence over the ones provided on the command line
111  // use this to make sure the node is placed on the provided namespace
112  // TODO(orduno) Pass a sub-node instead of creating a new node for better handling
113  // of the namespaces
114  rclcpp::NodeOptions().arguments({
115  "--ros-args", "-r", std::string("__ns:=") +
116  nav2_util::add_namespaces(parent_namespace, local_namespace),
117  "--ros-args", "-r", name + ":" + std::string("__node:=") + name
118  })),
119  name_(name),
120  parent_namespace_(parent_namespace),
121  default_plugins_{"static_layer", "obstacle_layer", "inflation_layer"},
122  default_types_{
123  "nav2_costmap_2d::StaticLayer",
124  "nav2_costmap_2d::ObstacleLayer",
125  "nav2_costmap_2d::InflationLayer"}
126 {
127  RCLCPP_INFO(get_logger(), "Creating Costmap");
128 
129  declare_parameter("always_send_full_costmap", rclcpp::ParameterValue(false));
130  declare_parameter("footprint_padding", rclcpp::ParameterValue(0.01f));
131  declare_parameter("footprint", rclcpp::ParameterValue(std::string("[]")));
132  declare_parameter("global_frame", rclcpp::ParameterValue(std::string("map")));
133  declare_parameter("height", rclcpp::ParameterValue(5));
134  declare_parameter("width", rclcpp::ParameterValue(5));
135  declare_parameter("lethal_cost_threshold", rclcpp::ParameterValue(100));
136  declare_parameter(
137  "map_topic", rclcpp::ParameterValue(
138  (parent_namespace_ == "/" ? "/" : parent_namespace_ + "/") + std::string("map")));
139  declare_parameter("observation_sources", rclcpp::ParameterValue(std::string("")));
140  declare_parameter("origin_x", rclcpp::ParameterValue(0.0));
141  declare_parameter("origin_y", rclcpp::ParameterValue(0.0));
142  declare_parameter("plugins", rclcpp::ParameterValue(default_plugins_));
143  declare_parameter("filters", rclcpp::ParameterValue(std::vector<std::string>()));
144  declare_parameter("publish_frequency", rclcpp::ParameterValue(1.0));
145  declare_parameter("resolution", rclcpp::ParameterValue(0.1));
146  declare_parameter("robot_base_frame", rclcpp::ParameterValue(std::string("base_link")));
147  declare_parameter("robot_radius", rclcpp::ParameterValue(0.1));
148  declare_parameter("rolling_window", rclcpp::ParameterValue(false));
149  declare_parameter("track_unknown_space", rclcpp::ParameterValue(false));
150  declare_parameter("transform_tolerance", rclcpp::ParameterValue(0.3));
151  declare_parameter("trinary_costmap", rclcpp::ParameterValue(true));
152  declare_parameter("unknown_cost_value", rclcpp::ParameterValue(static_cast<unsigned char>(0xff)));
153  declare_parameter("update_frequency", rclcpp::ParameterValue(5.0));
154  declare_parameter("use_maximum", rclcpp::ParameterValue(false));
155 }
156 
158 {
159 }
160 
161 nav2_util::CallbackReturn
162 Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
163 {
164  RCLCPP_INFO(get_logger(), "Configuring");
165  getParameters();
166 
167  callback_group_ = create_callback_group(
168  rclcpp::CallbackGroupType::MutuallyExclusive, false);
169 
170  // Create the costmap itself
171  layered_costmap_ = std::make_unique<LayeredCostmap>(
172  global_frame_, rolling_window_, track_unknown_space_);
173 
174  if (!layered_costmap_->isSizeLocked()) {
175  layered_costmap_->resizeMap(
176  (unsigned int)(map_width_meters_ / resolution_),
177  (unsigned int)(map_height_meters_ / resolution_), resolution_, origin_x_, origin_y_);
178  }
179 
180  // Create the transform-related objects
181  tf_buffer_ = std::make_shared<tf2_ros::Buffer>(get_clock());
182  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
183  get_node_base_interface(),
184  get_node_timers_interface(),
185  callback_group_);
186  tf_buffer_->setCreateTimerInterface(timer_interface);
187  tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
188 
189  // Then load and add the plug-ins to the costmap
190  for (unsigned int i = 0; i < plugin_names_.size(); ++i) {
191  RCLCPP_INFO(get_logger(), "Using plugin \"%s\"", plugin_names_[i].c_str());
192 
193  std::shared_ptr<Layer> plugin = plugin_loader_.createSharedInstance(plugin_types_[i]);
194 
195  // lock the costmap because no update is allowed until the plugin is initialized
196  std::unique_lock<Costmap2D::mutex_t> lock(*(layered_costmap_->getCostmap()->getMutex()));
197 
198  layered_costmap_->addPlugin(plugin);
199 
200  // TODO(mjeronimo): instead of get(), use a shared ptr
201  plugin->initialize(
202  layered_costmap_.get(), plugin_names_[i], tf_buffer_.get(),
203  shared_from_this(), callback_group_);
204 
205  lock.unlock();
206 
207  RCLCPP_INFO(get_logger(), "Initialized plugin \"%s\"", plugin_names_[i].c_str());
208  }
209  // and costmap filters as well
210  for (unsigned int i = 0; i < filter_names_.size(); ++i) {
211  RCLCPP_INFO(get_logger(), "Using costmap filter \"%s\"", filter_names_[i].c_str());
212 
213  std::shared_ptr<Layer> filter = plugin_loader_.createSharedInstance(filter_types_[i]);
214 
215  // lock the costmap because no update is allowed until the filter is initialized
216  std::unique_lock<Costmap2D::mutex_t> lock(*(layered_costmap_->getCostmap()->getMutex()));
217 
218  layered_costmap_->addFilter(filter);
219 
220  filter->initialize(
221  layered_costmap_.get(), filter_names_[i], tf_buffer_.get(),
222  shared_from_this(), callback_group_);
223 
224  lock.unlock();
225 
226  RCLCPP_INFO(get_logger(), "Initialized costmap filter \"%s\"", filter_names_[i].c_str());
227  }
228 
229  // Create the publishers and subscribers
230  footprint_sub_ = create_subscription<geometry_msgs::msg::Polygon>(
231  "footprint",
232  rclcpp::SystemDefaultsQoS(),
233  std::bind(&Costmap2DROS::setRobotFootprintPolygon, this, std::placeholders::_1));
234 
235  footprint_pub_ = create_publisher<geometry_msgs::msg::PolygonStamped>(
236  "published_footprint", rclcpp::SystemDefaultsQoS());
237 
238  costmap_publisher_ = std::make_unique<Costmap2DPublisher>(
240  layered_costmap_->getCostmap(), global_frame_,
241  "costmap", always_send_full_costmap_);
242 
243  // Set the footprint
244  if (use_radius_) {
246  } else {
247  std::vector<geometry_msgs::msg::Point> new_footprint;
248  makeFootprintFromString(footprint_, new_footprint);
249  setRobotFootprint(new_footprint);
250  }
251 
252  // Add cleaning service
253  clear_costmap_service_ = std::make_unique<ClearCostmapService>(shared_from_this(), *this);
254 
255  executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
256  executor_->add_callback_group(callback_group_, get_node_base_interface());
257  executor_thread_ = std::make_unique<nav2_util::NodeThread>(executor_);
258  return nav2_util::CallbackReturn::SUCCESS;
259 }
260 
261 nav2_util::CallbackReturn
262 Costmap2DROS::on_activate(const rclcpp_lifecycle::State & /*state*/)
263 {
264  RCLCPP_INFO(get_logger(), "Activating");
265 
266  costmap_publisher_->on_activate();
267  footprint_pub_->on_activate();
268 
269  // First, make sure that the transform between the robot base frame
270  // and the global frame is available
271 
272  std::string tf_error;
273 
274  RCLCPP_INFO(get_logger(), "Checking transform");
275  rclcpp::Rate r(2);
276  while (rclcpp::ok() &&
277  !tf_buffer_->canTransform(
278  global_frame_, robot_base_frame_, tf2::TimePointZero, &tf_error))
279  {
280  RCLCPP_INFO(
281  get_logger(), "Timed out waiting for transform from %s to %s"
282  " to become available, tf error: %s",
283  robot_base_frame_.c_str(), global_frame_.c_str(), tf_error.c_str());
284 
285  // The error string will accumulate and errors will typically be the same, so the last
286  // will do for the warning above. Reset the string here to avoid accumulation
287  tf_error.clear();
288  r.sleep();
289  }
290 
291  // Create a thread to handle updating the map
292  stopped_ = true; // to active plugins
293  stop_updates_ = false;
294  map_update_thread_shutdown_ = false;
295  map_update_thread_ = std::make_unique<std::thread>(
296  std::bind(&Costmap2DROS::mapUpdateLoop, this, map_update_frequency_));
297 
298  start();
299 
300  // Add callback for dynamic parameters
301  dyn_params_handler = this->add_on_set_parameters_callback(
302  std::bind(&Costmap2DROS::dynamicParametersCallback, this, _1));
303 
304  return nav2_util::CallbackReturn::SUCCESS;
305 }
306 
307 nav2_util::CallbackReturn
308 Costmap2DROS::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
309 {
310  RCLCPP_INFO(get_logger(), "Deactivating");
311 
312  dyn_params_handler.reset();
313 
314  stop();
315 
316  // Map thread stuff
317  map_update_thread_shutdown_ = true;
318 
319  if (map_update_thread_->joinable()) {
320  map_update_thread_->join();
321  }
322 
323  costmap_publisher_->on_deactivate();
324  footprint_pub_->on_deactivate();
325 
326  return nav2_util::CallbackReturn::SUCCESS;
327 }
328 
329 nav2_util::CallbackReturn
330 Costmap2DROS::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
331 {
332  RCLCPP_INFO(get_logger(), "Cleaning up");
333 
334  layered_costmap_.reset();
335 
336  tf_listener_.reset();
337  tf_buffer_.reset();
338 
339  footprint_sub_.reset();
340  footprint_pub_.reset();
341 
342  costmap_publisher_.reset();
343  clear_costmap_service_.reset();
344 
345  executor_thread_.reset();
346  return nav2_util::CallbackReturn::SUCCESS;
347 }
348 
349 nav2_util::CallbackReturn
350 Costmap2DROS::on_shutdown(const rclcpp_lifecycle::State &)
351 {
352  RCLCPP_INFO(get_logger(), "Shutting down");
353  return nav2_util::CallbackReturn::SUCCESS;
354 }
355 
356 void
358 {
359  RCLCPP_DEBUG(get_logger(), " getParameters");
360 
361  // Get all of the required parameters
362  get_parameter("always_send_full_costmap", always_send_full_costmap_);
363  get_parameter("footprint", footprint_);
364  get_parameter("footprint_padding", footprint_padding_);
365  get_parameter("global_frame", global_frame_);
366  get_parameter("height", map_height_meters_);
367  get_parameter("origin_x", origin_x_);
368  get_parameter("origin_y", origin_y_);
369  get_parameter("publish_frequency", map_publish_frequency_);
370  get_parameter("resolution", resolution_);
371  get_parameter("robot_base_frame", robot_base_frame_);
372  get_parameter("robot_radius", robot_radius_);
373  get_parameter("rolling_window", rolling_window_);
374  get_parameter("track_unknown_space", track_unknown_space_);
375  get_parameter("transform_tolerance", transform_tolerance_);
376  get_parameter("update_frequency", map_update_frequency_);
377  get_parameter("width", map_width_meters_);
378  get_parameter("plugins", plugin_names_);
379  get_parameter("filters", filter_names_);
380 
381  auto node = shared_from_this();
382 
383  if (plugin_names_ == default_plugins_) {
384  for (size_t i = 0; i < default_plugins_.size(); ++i) {
385  nav2_util::declare_parameter_if_not_declared(
386  node, default_plugins_[i] + ".plugin", rclcpp::ParameterValue(default_types_[i]));
387  }
388  }
389  plugin_types_.resize(plugin_names_.size());
390  filter_types_.resize(filter_names_.size());
391 
392  // 1. All plugins must have 'plugin' param defined in their namespace to define the plugin type
393  for (size_t i = 0; i < plugin_names_.size(); ++i) {
394  plugin_types_[i] = nav2_util::get_plugin_type_param(node, plugin_names_[i]);
395  }
396  for (size_t i = 0; i < filter_names_.size(); ++i) {
397  filter_types_[i] = nav2_util::get_plugin_type_param(node, filter_names_[i]);
398  }
399 
400  // 2. The map publish frequency cannot be 0 (to avoid a divde-by-zero)
401  if (map_publish_frequency_ > 0) {
402  publish_cycle_ = rclcpp::Duration::from_seconds(1 / map_publish_frequency_);
403  } else {
404  publish_cycle_ = rclcpp::Duration(-1s);
405  }
406 
407  // 3. If the footprint has been specified, it must be in the correct format
408  use_radius_ = true;
409 
410  if (footprint_ != "" && footprint_ != "[]") {
411  // Footprint parameter has been specified, try to convert it
412  std::vector<geometry_msgs::msg::Point> new_footprint;
413  if (makeFootprintFromString(footprint_, new_footprint)) {
414  // The specified footprint is valid, so we'll use that instead of the radius
415  use_radius_ = false;
416  } else {
417  // Footprint provided but invalid, so stay with the radius
418  RCLCPP_ERROR(
419  get_logger(), "The footprint parameter is invalid: \"%s\", using radius (%lf) instead",
420  footprint_.c_str(), robot_radius_);
421  }
422  }
423 }
424 
425 void
426 Costmap2DROS::setRobotFootprint(const std::vector<geometry_msgs::msg::Point> & points)
427 {
428  unpadded_footprint_ = points;
429  padded_footprint_ = points;
430  padFootprint(padded_footprint_, footprint_padding_);
431  layered_costmap_->setFootprint(padded_footprint_);
432 }
433 
434 void
436  const geometry_msgs::msg::Polygon::SharedPtr footprint)
437 {
438  setRobotFootprint(toPointVector(footprint));
439 }
440 
441 void
442 Costmap2DROS::getOrientedFootprint(std::vector<geometry_msgs::msg::Point> & oriented_footprint)
443 {
444  geometry_msgs::msg::PoseStamped global_pose;
445  if (!getRobotPose(global_pose)) {
446  return;
447  }
448 
449  double yaw = tf2::getYaw(global_pose.pose.orientation);
451  global_pose.pose.position.x, global_pose.pose.position.y, yaw,
452  padded_footprint_, oriented_footprint);
453 }
454 
455 void
457 {
458  RCLCPP_DEBUG(get_logger(), "mapUpdateLoop frequency: %lf", frequency);
459 
460  // the user might not want to run the loop every cycle
461  if (frequency == 0.0) {
462  return;
463  }
464 
465  RCLCPP_DEBUG(get_logger(), "Entering loop");
466 
467  rclcpp::WallRate r(frequency); // 200ms by default
468 
469  while (rclcpp::ok() && !map_update_thread_shutdown_) {
471 
472  // Execute after start() will complete plugins activation
473  if (!stopped_) {
474  // Lock while modifying layered costmap and publishing values
475  std::scoped_lock<std::mutex> lock(_dynamic_parameter_mutex);
476 
477  // Measure the execution time of the updateMap method
478  timer.start();
479  updateMap();
480  timer.end();
481 
482  RCLCPP_DEBUG(get_logger(), "Map update time: %.9f", timer.elapsed_time_in_seconds());
483  if (publish_cycle_ > rclcpp::Duration(0s) && layered_costmap_->isInitialized()) {
484  unsigned int x0, y0, xn, yn;
485  layered_costmap_->getBounds(&x0, &xn, &y0, &yn);
486  costmap_publisher_->updateBounds(x0, xn, y0, yn);
487 
488  auto current_time = now();
489  if ((last_publish_ + publish_cycle_ < current_time) || // publish_cycle_ is due
490  (current_time < last_publish_)) // time has moved backwards, probably due to a switch to sim_time // NOLINT
491  {
492  RCLCPP_DEBUG(get_logger(), "Publish costmap at %s", name_.c_str());
493  costmap_publisher_->publishCostmap();
494  last_publish_ = current_time;
495  }
496  }
497  }
498 
499  // Make sure to sleep for the remainder of our cycle time
500  r.sleep();
501 
502 #if 0
503  // TODO(bpwilcox): find ROS2 equivalent or port for r.cycletime()
504  if (r.period() > tf2::durationFromSec(1 / frequency)) {
505  RCLCPP_WARN(
506  get_logger(),
507  "Costmap2DROS: Map update loop missed its desired rate of %.4fHz... "
508  "the loop actually took %.4f seconds", frequency, r.period());
509  }
510 #endif
511  }
512 }
513 
514 void
516 {
517  RCLCPP_DEBUG(get_logger(), "Updating map...");
518 
519  if (!stop_updates_) {
520  // get global pose
521  geometry_msgs::msg::PoseStamped pose;
522  if (getRobotPose(pose)) {
523  const double & x = pose.pose.position.x;
524  const double & y = pose.pose.position.y;
525  const double yaw = tf2::getYaw(pose.pose.orientation);
526  layered_costmap_->updateMap(x, y, yaw);
527 
528  auto footprint = std::make_unique<geometry_msgs::msg::PolygonStamped>();
529  footprint->header = pose.header;
530  transformFootprint(x, y, yaw, padded_footprint_, *footprint);
531 
532  RCLCPP_DEBUG(get_logger(), "Publishing footprint");
533  footprint_pub_->publish(std::move(footprint));
534  initialized_ = true;
535  }
536  }
537 }
538 
539 void
541 {
542  RCLCPP_INFO(get_logger(), "start");
543  std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
544  std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
545 
546  // check if we're stopped or just paused
547  if (stopped_) {
548  // if we're stopped we need to re-subscribe to topics
549  for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
550  plugin != plugins->end();
551  ++plugin)
552  {
553  (*plugin)->activate();
554  }
555  for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
556  filter != filters->end();
557  ++filter)
558  {
559  (*filter)->activate();
560  }
561  stopped_ = false;
562  }
563  stop_updates_ = false;
564 
565  // block until the costmap is re-initialized.. meaning one update cycle has run
566  rclcpp::Rate r(20.0);
567  while (rclcpp::ok() && !initialized_) {
568  RCLCPP_DEBUG(get_logger(), "Sleeping, waiting for initialized_");
569  r.sleep();
570  }
571 }
572 
573 void
575 {
576  stop_updates_ = true;
577  // layered_costmap_ is set only if on_configure has been called
578  if (layered_costmap_) {
579  std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
580  std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
581 
582  // unsubscribe from topics
583  for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
584  plugin != plugins->end(); ++plugin)
585  {
586  (*plugin)->deactivate();
587  }
588  for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
589  filter != filters->end(); ++filter)
590  {
591  (*filter)->deactivate();
592  }
593  }
594  initialized_ = false;
595  stopped_ = true;
596 }
597 
598 void
600 {
601  stop_updates_ = true;
602  initialized_ = false;
603 }
604 
605 void
607 {
608  stop_updates_ = false;
609 
610  // block until the costmap is re-initialized.. meaning one update cycle has run
611  rclcpp::Rate r(100.0);
612  while (!initialized_) {
613  r.sleep();
614  }
615 }
616 
617 void
619 {
620  Costmap2D * top = layered_costmap_->getCostmap();
621  top->resetMap(0, 0, top->getSizeInCellsX(), top->getSizeInCellsY());
622 
623  // Reset each of the plugins
624  std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
625  std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
626  for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
627  plugin != plugins->end(); ++plugin)
628  {
629  (*plugin)->reset();
630  }
631  for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
632  filter != filters->end(); ++filter)
633  {
634  (*filter)->reset();
635  }
636 }
637 
638 bool
639 Costmap2DROS::getRobotPose(geometry_msgs::msg::PoseStamped & global_pose)
640 {
641  return nav2_util::getCurrentPose(
642  global_pose, *tf_buffer_,
644 }
645 
646 bool
648  const geometry_msgs::msg::PoseStamped & input_pose,
649  geometry_msgs::msg::PoseStamped & transformed_pose)
650 {
651  if (input_pose.header.frame_id == global_frame_) {
652  transformed_pose = input_pose;
653  return true;
654  } else {
655  return nav2_util::transformPoseInTargetFrame(
656  input_pose, transformed_pose, *tf_buffer_,
658  }
659 }
660 
661 rcl_interfaces::msg::SetParametersResult
662 Costmap2DROS::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
663 {
664  auto result = rcl_interfaces::msg::SetParametersResult();
665  bool resize_map = false;
666  std::lock_guard<std::mutex> lock_reinit(_dynamic_parameter_mutex);
667 
668  for (auto parameter : parameters) {
669  const auto & type = parameter.get_type();
670  const auto & name = parameter.get_name();
671 
672  if (type == ParameterType::PARAMETER_DOUBLE) {
673  if (name == "robot_radius") {
674  robot_radius_ = parameter.as_double();
675  // Set the footprint
676  if (use_radius_) {
678  }
679  } else if (name == "footprint_padding") {
680  footprint_padding_ = parameter.as_double();
681  padded_footprint_ = unpadded_footprint_;
682  padFootprint(padded_footprint_, footprint_padding_);
683  layered_costmap_->setFootprint(padded_footprint_);
684  } else if (name == "transform_tolerance") {
685  transform_tolerance_ = parameter.as_double();
686  } else if (name == "publish_frequency") {
687  map_publish_frequency_ = parameter.as_double();
688  if (map_publish_frequency_ > 0) {
689  publish_cycle_ = rclcpp::Duration::from_seconds(1 / map_publish_frequency_);
690  } else {
691  publish_cycle_ = rclcpp::Duration(-1s);
692  }
693  } else if (name == "resolution") {
694  resize_map = true;
695  resolution_ = parameter.as_double();
696  } else if (name == "origin_x") {
697  resize_map = true;
698  origin_x_ = parameter.as_double();
699  } else if (name == "origin_y") {
700  resize_map = true;
701  origin_y_ = parameter.as_double();
702  }
703  } else if (type == ParameterType::PARAMETER_INTEGER) {
704  if (name == "width") {
705  if (parameter.as_int() > 0) {
706  resize_map = true;
707  map_width_meters_ = parameter.as_int();
708  } else {
709  RCLCPP_ERROR(
710  get_logger(), "You try to set width of map to be negative or zero,"
711  " this isn't allowed, please give a positive value.");
712  result.successful = false;
713  return result;
714  }
715  } else if (name == "height") {
716  if (parameter.as_int() > 0) {
717  resize_map = true;
718  map_height_meters_ = parameter.as_int();
719  } else {
720  RCLCPP_ERROR(
721  get_logger(), "You try to set height of map to be negative or zero,"
722  " this isn't allowed, please give a positive value.");
723  result.successful = false;
724  return result;
725  }
726  }
727  } else if (type == ParameterType::PARAMETER_STRING) {
728  if (name == "footprint") {
729  footprint_ = parameter.as_string();
730  std::vector<geometry_msgs::msg::Point> new_footprint;
731  if (makeFootprintFromString(footprint_, new_footprint)) {
732  setRobotFootprint(new_footprint);
733  }
734  } else if (name == "robot_base_frame") {
735  // First, make sure that the transform between the robot base frame
736  // and the global frame is available
737  std::string tf_error;
738  RCLCPP_INFO(get_logger(), "Checking transform");
739  if (!tf_buffer_->canTransform(
740  global_frame_, parameter.as_string(), tf2::TimePointZero,
741  tf2::durationFromSec(1.0), &tf_error))
742  {
743  RCLCPP_WARN(
744  get_logger(), "Timed out waiting for transform from %s to %s"
745  " to become available, tf error: %s",
746  parameter.as_string().c_str(), global_frame_.c_str(), tf_error.c_str());
747  RCLCPP_WARN(
748  get_logger(), "Rejecting robot_base_frame change to %s , leaving it to its original"
749  " value of %s", parameter.as_string().c_str(), robot_base_frame_.c_str());
750  result.successful = false;
751  return result;
752  }
753  robot_base_frame_ = parameter.as_string();
754  }
755  }
756  }
757 
758  if (resize_map && !layered_costmap_->isSizeLocked()) {
759  layered_costmap_->resizeMap(
760  (unsigned int)(map_width_meters_ / resolution_),
761  (unsigned int)(map_height_meters_ / resolution_), resolution_, origin_x_, origin_y_);
762  updateMap();
763  }
764 
765  result.successful = true;
766  return result;
767 }
768 
769 } // namespace nav2_costmap_2d
A ROS wrapper for a 2D Costmap. Handles subscribing to topics that provide observations about obstacl...
Costmap2DROS(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for the wrapper.
void mapUpdateLoop(double frequency)
Function on timer for costmap update.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate node.
void getOrientedFootprint(std::vector< geometry_msgs::msg::Point > &oriented_footprint)
Build the oriented footprint of the robot at the robot's current pose.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
bool getRobotPose(geometry_msgs::msg::PoseStamped &global_pose)
Get the pose of the robot in the global frame of the costmap.
void getParameters()
Get parameters for node.
void pause()
Stops the costmap from updating, but sensor data still comes in over the wire.
void setRobotFootprintPolygon(const geometry_msgs::msg::Polygon::SharedPtr footprint)
Set the footprint of the robot to be the given polygon, padded by footprint_padding.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
shutdown node
double transform_tolerance_
The timeout before transform errors.
bool rolling_window_
Whether to use a rolling window version of the costmap.
void resume()
Resumes costmap updates.
void updateMap()
Update the map with the layered costmap / plugins.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate node.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure node.
void setRobotFootprint(const std::vector< geometry_msgs::msg::Point > &points)
Set the footprint of the robot to be the given set of points, padded by footprint_padding.
void resetLayers()
Reset each individual layer.
bool transformPoseToGlobalFrame(const geometry_msgs::msg::PoseStamped &input_pose, geometry_msgs::msg::PoseStamped &transformed_pose)
Transform the input_pose in the global frame of the costmap.
std::string global_frame_
The global frame for the costmap.
void start()
Subscribes to sensor topics if necessary and starts costmap updates, can be called to restart the cos...
void stop()
Stops costmap updates and unsubscribes from sensor topics.
std::string robot_base_frame_
The frame_id of the robot base.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Cleanup node.
std::unique_ptr< std::thread > map_update_thread_
A thread for updating the map.
bool is_lifecycle_follower_
whether is a child-LifecycleNode or an independent node
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
Reset the costmap in bounds.
Definition: costmap_2d.cpp:130
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:501
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:506
Measures execution time of code between calls to start and end.
void start()
Call just prior to code you want to measure.
double elapsed_time_in_seconds()
Extract the measured time as a floating point number of seconds.
void end()
Call just after the code you want to measure.
std::shared_ptr< nav2_util::LifecycleNode > shared_from_this()
Get a shared pointer of this.
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::msg::Point > &footprint_spec, std::vector< geometry_msgs::msg::Point > &oriented_footprint)
Given a pose and base footprint, build the oriented footprint of the robot (list of Points)
Definition: footprint.cpp:109
bool makeFootprintFromString(const std::string &footprint_string, std::vector< geometry_msgs::msg::Point > &footprint)
Make the footprint from the given string.
Definition: footprint.cpp:174
void padFootprint(std::vector< geometry_msgs::msg::Point > &footprint, double padding)
Adds the specified amount of padding to the footprint (in place)
Definition: footprint.cpp:144
std::vector< geometry_msgs::msg::Point > makeFootprintFromRadius(double radius)
Create a circular footprint from a given radius.
Definition: footprint.cpp:155
std::vector< geometry_msgs::msg::Point > toPointVector(geometry_msgs::msg::Polygon::SharedPtr polygon)
Convert Polygon msg to vector of Points.
Definition: footprint.cpp:100