Nav2 Navigation Stack - jazzy  jazzy
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, const bool & use_sim_time)
62 : Costmap2DROS(name, "/", name, use_sim_time) {}
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  declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map")));
74  is_lifecycle_follower_ = false;
75  init();
76 }
77 
79  const std::string & name,
80  const std::string & parent_namespace,
81  const std::string & local_namespace,
82  const bool & use_sim_time)
83 : nav2_util::LifecycleNode(name, "",
84  // NodeOption arguments take precedence over the ones provided on the command line
85  // use this to make sure the node is placed on the provided namespace
86  // TODO(orduno) Pass a sub-node instead of creating a new node for better handling
87  // of the namespaces
88  rclcpp::NodeOptions().arguments({
89  "--ros-args", "-r", std::string("__ns:=") +
90  nav2_util::add_namespaces(parent_namespace, local_namespace),
91  "--ros-args", "-r", name + ":" + std::string("__node:=") + name,
92  "--ros-args", "-p", "use_sim_time:=" + std::string(use_sim_time ? "true" : "false"),
93  })),
94  name_(name),
95  parent_namespace_(parent_namespace),
96  default_plugins_{"static_layer", "obstacle_layer", "inflation_layer"},
97  default_types_{
98  "nav2_costmap_2d::StaticLayer",
99  "nav2_costmap_2d::ObstacleLayer",
100  "nav2_costmap_2d::InflationLayer"}
101 {
102  declare_parameter(
103  "map_topic", rclcpp::ParameterValue(
104  (parent_namespace_ == "/" ? "/" : parent_namespace_ + "/") + std::string("map")));
105  init();
106 }
107 
109 {
110  RCLCPP_INFO(get_logger(), "Creating Costmap");
111 
112  declare_parameter("always_send_full_costmap", rclcpp::ParameterValue(false));
113  declare_parameter("map_vis_z", rclcpp::ParameterValue(0.0));
114  declare_parameter("footprint_padding", rclcpp::ParameterValue(0.01f));
115  declare_parameter("footprint", rclcpp::ParameterValue(std::string("[]")));
116  declare_parameter("global_frame", rclcpp::ParameterValue(std::string("map")));
117  declare_parameter("height", rclcpp::ParameterValue(5));
118  declare_parameter("width", rclcpp::ParameterValue(5));
119  declare_parameter("lethal_cost_threshold", rclcpp::ParameterValue(100));
120  declare_parameter("observation_sources", rclcpp::ParameterValue(std::string("")));
121  declare_parameter("origin_x", rclcpp::ParameterValue(0.0));
122  declare_parameter("origin_y", rclcpp::ParameterValue(0.0));
123  declare_parameter("plugins", rclcpp::ParameterValue(default_plugins_));
124  declare_parameter("filters", rclcpp::ParameterValue(std::vector<std::string>()));
125  declare_parameter("publish_frequency", rclcpp::ParameterValue(1.0));
126  declare_parameter("resolution", rclcpp::ParameterValue(0.1));
127  declare_parameter("robot_base_frame", rclcpp::ParameterValue(std::string("base_link")));
128  declare_parameter("robot_radius", rclcpp::ParameterValue(0.1));
129  declare_parameter("rolling_window", rclcpp::ParameterValue(false));
130  declare_parameter("track_unknown_space", rclcpp::ParameterValue(false));
131  declare_parameter("transform_tolerance", rclcpp::ParameterValue(0.3));
132  declare_parameter("initial_transform_timeout", rclcpp::ParameterValue(60.0));
133  declare_parameter("trinary_costmap", rclcpp::ParameterValue(true));
134  declare_parameter("unknown_cost_value", rclcpp::ParameterValue(static_cast<unsigned char>(0xff)));
135  declare_parameter("update_frequency", rclcpp::ParameterValue(5.0));
136  declare_parameter("use_maximum", rclcpp::ParameterValue(false));
137 }
138 
140 {
141 }
142 
143 nav2_util::CallbackReturn
144 Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
145 {
146  RCLCPP_INFO(get_logger(), "Configuring");
147  try {
148  getParameters();
149  } catch (const std::exception & e) {
150  RCLCPP_ERROR(
151  get_logger(), "Failed to configure costmap! %s.", e.what());
152  return nav2_util::CallbackReturn::FAILURE;
153  }
154 
155  callback_group_ = create_callback_group(
156  rclcpp::CallbackGroupType::MutuallyExclusive, false);
157 
158  // Create the costmap itself
159  layered_costmap_ = std::make_unique<LayeredCostmap>(
160  global_frame_, rolling_window_, track_unknown_space_);
161 
162  if (!layered_costmap_->isSizeLocked()) {
163  layered_costmap_->resizeMap(
164  (unsigned int)(map_width_meters_ / resolution_),
165  (unsigned int)(map_height_meters_ / resolution_), resolution_, origin_x_, origin_y_);
166  }
167 
168  // Create the transform-related objects
169  tf_buffer_ = std::make_shared<tf2_ros::Buffer>(get_clock());
170  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
171  get_node_base_interface(),
172  get_node_timers_interface(),
173  callback_group_);
174  tf_buffer_->setCreateTimerInterface(timer_interface);
175  tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
176 
177  // Then load and add the plug-ins to the costmap
178  for (unsigned int i = 0; i < plugin_names_.size(); ++i) {
179  RCLCPP_INFO(get_logger(), "Using plugin \"%s\"", plugin_names_[i].c_str());
180 
181  std::shared_ptr<Layer> plugin = plugin_loader_.createSharedInstance(plugin_types_[i]);
182 
183  // lock the costmap because no update is allowed until the plugin is initialized
184  std::unique_lock<Costmap2D::mutex_t> lock(*(layered_costmap_->getCostmap()->getMutex()));
185 
186  layered_costmap_->addPlugin(plugin);
187 
188  // TODO(mjeronimo): instead of get(), use a shared ptr
189  try {
190  plugin->initialize(layered_costmap_.get(), plugin_names_[i], tf_buffer_.get(),
191  shared_from_this(), callback_group_);
192  } catch (const std::exception & e) {
193  RCLCPP_ERROR(get_logger(), "Failed to initialize costmap plugin %s! %s.",
194  plugin_names_[i].c_str(), e.what());
195  return nav2_util::CallbackReturn::FAILURE;
196  }
197 
198  lock.unlock();
199 
200  RCLCPP_INFO(get_logger(), "Initialized plugin \"%s\"", plugin_names_[i].c_str());
201  }
202  // and costmap filters as well
203  for (unsigned int i = 0; i < filter_names_.size(); ++i) {
204  RCLCPP_INFO(get_logger(), "Using costmap filter \"%s\"", filter_names_[i].c_str());
205 
206  std::shared_ptr<Layer> filter = plugin_loader_.createSharedInstance(filter_types_[i]);
207 
208  // lock the costmap because no update is allowed until the filter is initialized
209  std::unique_lock<Costmap2D::mutex_t> lock(*(layered_costmap_->getCostmap()->getMutex()));
210 
211  layered_costmap_->addFilter(filter);
212 
213  filter->initialize(
214  layered_costmap_.get(), filter_names_[i], tf_buffer_.get(),
215  shared_from_this(), callback_group_);
216 
217  lock.unlock();
218 
219  RCLCPP_INFO(get_logger(), "Initialized costmap filter \"%s\"", filter_names_[i].c_str());
220  }
221 
222  // Create the publishers and subscribers
223  footprint_sub_ = create_subscription<geometry_msgs::msg::Polygon>(
224  "footprint",
225  rclcpp::SystemDefaultsQoS(),
226  std::bind(&Costmap2DROS::setRobotFootprintPolygon, this, std::placeholders::_1));
227 
228  footprint_pub_ = create_publisher<geometry_msgs::msg::PolygonStamped>(
229  "published_footprint", rclcpp::SystemDefaultsQoS());
230 
231  costmap_publisher_ = std::make_unique<Costmap2DPublisher>(
233  layered_costmap_->getCostmap(), global_frame_,
234  "costmap", always_send_full_costmap_, map_vis_z_);
235 
236  auto layers = layered_costmap_->getPlugins();
237 
238  for (auto & layer : *layers) {
239  auto costmap_layer = std::dynamic_pointer_cast<CostmapLayer>(layer);
240  if (costmap_layer != nullptr) {
241  layer_publishers_.emplace_back(
242  std::make_unique<Costmap2DPublisher>(
244  costmap_layer.get(), global_frame_,
245  layer->getName(), always_send_full_costmap_, map_vis_z_)
246  );
247  }
248  }
249 
250  // Set the footprint
251  if (use_radius_) {
253  } else {
254  std::vector<geometry_msgs::msg::Point> new_footprint;
255  makeFootprintFromString(footprint_, new_footprint);
256  setRobotFootprint(new_footprint);
257  }
258 
259  // Service to get the cost at a point
260  get_cost_service_ = create_service<nav2_msgs::srv::GetCost>(
261  "get_cost_" + getName(),
262  std::bind(&Costmap2DROS::getCostCallback, this, std::placeholders::_1, std::placeholders::_2,
263  std::placeholders::_3));
264 
265  // Add cleaning service
266  clear_costmap_service_ = std::make_unique<ClearCostmapService>(shared_from_this(), *this);
267 
268  executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
269  executor_->add_callback_group(callback_group_, get_node_base_interface());
270  executor_thread_ = std::make_unique<nav2_util::NodeThread>(executor_);
271  return nav2_util::CallbackReturn::SUCCESS;
272 }
273 
274 nav2_util::CallbackReturn
275 Costmap2DROS::on_activate(const rclcpp_lifecycle::State & /*state*/)
276 {
277  RCLCPP_INFO(get_logger(), "Activating");
278 
279  // First, make sure that the transform between the robot base frame
280  // and the global frame is available
281 
282  std::string tf_error;
283 
284  RCLCPP_INFO(get_logger(), "Checking transform");
285  rclcpp::Rate r(2);
286  const auto initial_transform_timeout = rclcpp::Duration::from_seconds(
288  const auto initial_transform_timeout_point = now() + initial_transform_timeout;
289  while (rclcpp::ok() &&
290  !tf_buffer_->canTransform(
291  global_frame_, robot_base_frame_, tf2::TimePointZero, &tf_error))
292  {
293  RCLCPP_INFO(
294  get_logger(), "Timed out waiting for transform from %s to %s"
295  " to become available, tf error: %s",
296  robot_base_frame_.c_str(), global_frame_.c_str(), tf_error.c_str());
297 
298  // Check timeout
299  if (now() > initial_transform_timeout_point) {
300  RCLCPP_ERROR(
301  get_logger(),
302  "Failed to activate %s because "
303  "transform from %s to %s did not become available before timeout",
304  get_name(), robot_base_frame_.c_str(), global_frame_.c_str());
305 
306  return nav2_util::CallbackReturn::FAILURE;
307  }
308 
309  // The error string will accumulate and errors will typically be the same, so the last
310  // will do for the warning above. Reset the string here to avoid accumulation
311  tf_error.clear();
312  r.sleep();
313  }
314 
315  // Activate publishers
316  footprint_pub_->on_activate();
317  costmap_publisher_->on_activate();
318 
319  for (auto & layer_pub : layer_publishers_) {
320  layer_pub->on_activate();
321  }
322 
323  // Create a thread to handle updating the map
324  stopped_ = true; // to active plugins
325  stop_updates_ = false;
326  map_update_thread_shutdown_ = false;
327  map_update_thread_ = std::make_unique<std::thread>(
328  std::bind(&Costmap2DROS::mapUpdateLoop, this, map_update_frequency_));
329 
330  start();
331 
332  // Add callback for dynamic parameters
333  dyn_params_handler = this->add_on_set_parameters_callback(
334  std::bind(&Costmap2DROS::dynamicParametersCallback, this, _1));
335 
336  return nav2_util::CallbackReturn::SUCCESS;
337 }
338 
339 nav2_util::CallbackReturn
340 Costmap2DROS::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
341 {
342  RCLCPP_INFO(get_logger(), "Deactivating");
343 
344  remove_on_set_parameters_callback(dyn_params_handler.get());
345  dyn_params_handler.reset();
346 
347  stop();
348 
349  // Map thread stuff
350  map_update_thread_shutdown_ = true;
351 
352  if (map_update_thread_->joinable()) {
353  map_update_thread_->join();
354  }
355 
356  footprint_pub_->on_deactivate();
357  costmap_publisher_->on_deactivate();
358 
359  for (auto & layer_pub : layer_publishers_) {
360  layer_pub->on_deactivate();
361  }
362 
363  return nav2_util::CallbackReturn::SUCCESS;
364 }
365 
366 nav2_util::CallbackReturn
367 Costmap2DROS::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
368 {
369  RCLCPP_INFO(get_logger(), "Cleaning up");
370  executor_thread_.reset();
371 
372  costmap_publisher_.reset();
373  clear_costmap_service_.reset();
374 
375  layer_publishers_.clear();
376 
377  layered_costmap_.reset();
378 
379  tf_listener_.reset();
380  tf_buffer_.reset();
381 
382  footprint_sub_.reset();
383  footprint_pub_.reset();
384 
385  return nav2_util::CallbackReturn::SUCCESS;
386 }
387 
388 nav2_util::CallbackReturn
389 Costmap2DROS::on_shutdown(const rclcpp_lifecycle::State &)
390 {
391  RCLCPP_INFO(get_logger(), "Shutting down");
392  return nav2_util::CallbackReturn::SUCCESS;
393 }
394 
395 void
397 {
398  RCLCPP_DEBUG(get_logger(), " getParameters");
399 
400  // Get all of the required parameters
401  get_parameter("always_send_full_costmap", always_send_full_costmap_);
402  get_parameter("map_vis_z", map_vis_z_);
403  get_parameter("footprint", footprint_);
404  get_parameter("footprint_padding", footprint_padding_);
405  get_parameter("global_frame", global_frame_);
406  get_parameter("height", map_height_meters_);
407  get_parameter("origin_x", origin_x_);
408  get_parameter("origin_y", origin_y_);
409  get_parameter("publish_frequency", map_publish_frequency_);
410  get_parameter("resolution", resolution_);
411  get_parameter("robot_base_frame", robot_base_frame_);
412  get_parameter("robot_radius", robot_radius_);
413  get_parameter("rolling_window", rolling_window_);
414  get_parameter("track_unknown_space", track_unknown_space_);
415  get_parameter("transform_tolerance", transform_tolerance_);
416  get_parameter("initial_transform_timeout", initial_transform_timeout_);
417  get_parameter("update_frequency", map_update_frequency_);
418  get_parameter("width", map_width_meters_);
419  get_parameter("plugins", plugin_names_);
420  get_parameter("filters", filter_names_);
421 
422  auto node = shared_from_this();
423 
424  if (plugin_names_ == default_plugins_) {
425  for (size_t i = 0; i < default_plugins_.size(); ++i) {
426  nav2_util::declare_parameter_if_not_declared(
427  node, default_plugins_[i] + ".plugin", rclcpp::ParameterValue(default_types_[i]));
428  }
429  }
430  plugin_types_.resize(plugin_names_.size());
431  filter_types_.resize(filter_names_.size());
432 
433  // 1. All plugins must have 'plugin' param defined in their namespace to define the plugin type
434  for (size_t i = 0; i < plugin_names_.size(); ++i) {
435  plugin_types_[i] = nav2_util::get_plugin_type_param(node, plugin_names_[i]);
436  }
437  for (size_t i = 0; i < filter_names_.size(); ++i) {
438  filter_types_[i] = nav2_util::get_plugin_type_param(node, filter_names_[i]);
439  }
440 
441  // 2. The map publish frequency cannot be 0 (to avoid a divde-by-zero)
442  if (map_publish_frequency_ > 0) {
443  publish_cycle_ = rclcpp::Duration::from_seconds(1 / map_publish_frequency_);
444  } else {
445  publish_cycle_ = rclcpp::Duration(-1s);
446  }
447 
448  // 3. If the footprint has been specified, it must be in the correct format
449  use_radius_ = true;
450 
451  if (footprint_ != "" && footprint_ != "[]") {
452  // Footprint parameter has been specified, try to convert it
453  std::vector<geometry_msgs::msg::Point> new_footprint;
454  if (makeFootprintFromString(footprint_, new_footprint)) {
455  // The specified footprint is valid, so we'll use that instead of the radius
456  use_radius_ = false;
457  } else {
458  // Footprint provided but invalid, so stay with the radius
459  RCLCPP_ERROR(
460  get_logger(), "The footprint parameter is invalid: \"%s\", using radius (%lf) instead",
461  footprint_.c_str(), robot_radius_);
462  }
463  }
464 
465  // 4. The width and height of map cannot be negative or 0 (to avoid abnoram memory usage)
466  if (map_width_meters_ <= 0) {
467  RCLCPP_ERROR(
468  get_logger(), "You try to set width of map to be negative or zero,"
469  " this isn't allowed, please give a positive value.");
470  }
471  if (map_height_meters_ <= 0) {
472  RCLCPP_ERROR(
473  get_logger(), "You try to set height of map to be negative or zero,"
474  " this isn't allowed, please give a positive value.");
475  }
476 }
477 
478 void
479 Costmap2DROS::setRobotFootprint(const std::vector<geometry_msgs::msg::Point> & points)
480 {
481  unpadded_footprint_ = points;
482  padded_footprint_ = points;
483  padFootprint(padded_footprint_, footprint_padding_);
484  layered_costmap_->setFootprint(padded_footprint_);
485 }
486 
487 void
489  const geometry_msgs::msg::Polygon::SharedPtr footprint)
490 {
491  setRobotFootprint(toPointVector(footprint));
492 }
493 
494 void
495 Costmap2DROS::getOrientedFootprint(std::vector<geometry_msgs::msg::Point> & oriented_footprint)
496 {
497  geometry_msgs::msg::PoseStamped global_pose;
498  if (!getRobotPose(global_pose)) {
499  return;
500  }
501 
502  double yaw = tf2::getYaw(global_pose.pose.orientation);
504  global_pose.pose.position.x, global_pose.pose.position.y, yaw,
505  padded_footprint_, oriented_footprint);
506 }
507 
508 void
510 {
511  RCLCPP_DEBUG(get_logger(), "mapUpdateLoop frequency: %lf", frequency);
512 
513  // the user might not want to run the loop every cycle
514  if (frequency == 0.0) {
515  return;
516  }
517 
518  RCLCPP_DEBUG(get_logger(), "Entering loop");
519 
520  rclcpp::WallRate r(frequency); // 200ms by default
521 
522  while (rclcpp::ok() && !map_update_thread_shutdown_) {
524 
525  // Execute after start() will complete plugins activation
526  if (!stopped_) {
527  // Lock while modifying layered costmap and publishing values
528  std::scoped_lock<std::mutex> lock(_dynamic_parameter_mutex);
529 
530  // Measure the execution time of the updateMap method
531  timer.start();
532  updateMap();
533  timer.end();
534 
535  RCLCPP_DEBUG(get_logger(), "Map update time: %.9f", timer.elapsed_time_in_seconds());
536  if (publish_cycle_ > rclcpp::Duration(0s) && layered_costmap_->isInitialized()) {
537  unsigned int x0, y0, xn, yn;
538  layered_costmap_->getBounds(&x0, &xn, &y0, &yn);
539  costmap_publisher_->updateBounds(x0, xn, y0, yn);
540 
541  for (auto & layer_pub : layer_publishers_) {
542  layer_pub->updateBounds(x0, xn, y0, yn);
543  }
544 
545  auto current_time = now();
546  if ((last_publish_ + publish_cycle_ < current_time) || // publish_cycle_ is due
547  (current_time <
548  last_publish_)) // time has moved backwards, probably due to a switch to sim_time // NOLINT
549  {
550  RCLCPP_DEBUG(get_logger(), "Publish costmap at %s", name_.c_str());
551  costmap_publisher_->publishCostmap();
552 
553  for (auto & layer_pub : layer_publishers_) {
554  layer_pub->publishCostmap();
555  }
556 
557  last_publish_ = current_time;
558  }
559  }
560  }
561 
562  // Make sure to sleep for the remainder of our cycle time
563  r.sleep();
564 
565 #if 0
566  // TODO(bpwilcox): find ROS2 equivalent or port for r.cycletime()
567  if (r.period() > tf2::durationFromSec(1 / frequency)) {
568  RCLCPP_WARN(
569  get_logger(),
570  "Costmap2DROS: Map update loop missed its desired rate of %.4fHz... "
571  "the loop actually took %.4f seconds", frequency, r.period());
572  }
573 #endif
574  }
575 }
576 
577 void
579 {
580  RCLCPP_DEBUG(get_logger(), "Updating map...");
581 
582  if (!stop_updates_) {
583  // get global pose
584  geometry_msgs::msg::PoseStamped pose;
585  if (getRobotPose(pose)) {
586  const double & x = pose.pose.position.x;
587  const double & y = pose.pose.position.y;
588  const double yaw = tf2::getYaw(pose.pose.orientation);
589  layered_costmap_->updateMap(x, y, yaw);
590 
591  auto footprint = std::make_unique<geometry_msgs::msg::PolygonStamped>();
592  footprint->header = pose.header;
593  transformFootprint(x, y, yaw, padded_footprint_, *footprint);
594 
595  RCLCPP_DEBUG(get_logger(), "Publishing footprint");
596  footprint_pub_->publish(std::move(footprint));
597  initialized_ = true;
598  }
599  }
600 }
601 
602 void
604 {
605  RCLCPP_INFO(get_logger(), "start");
606  std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
607  std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
608 
609  // check if we're stopped or just paused
610  if (stopped_) {
611  // if we're stopped we need to re-subscribe to topics
612  for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
613  plugin != plugins->end();
614  ++plugin)
615  {
616  (*plugin)->activate();
617  }
618  for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
619  filter != filters->end();
620  ++filter)
621  {
622  (*filter)->activate();
623  }
624  stopped_ = false;
625  }
626  stop_updates_ = false;
627 
628  // block until the costmap is re-initialized.. meaning one update cycle has run
629  rclcpp::Rate r(20.0);
630  while (rclcpp::ok() && !initialized_) {
631  RCLCPP_DEBUG(get_logger(), "Sleeping, waiting for initialized_");
632  r.sleep();
633  }
634 }
635 
636 void
638 {
639  stop_updates_ = true;
640 
641  // layered_costmap_ is set only if on_configure has been called
642  if (layered_costmap_) {
643  std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
644  std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
645 
646  // unsubscribe from topics
647  for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
648  plugin != plugins->end(); ++plugin)
649  {
650  (*plugin)->deactivate();
651  }
652  for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
653  filter != filters->end(); ++filter)
654  {
655  (*filter)->deactivate();
656  }
657  }
658  initialized_ = false;
659  stopped_ = true;
660 }
661 
662 void
664 {
665  stop_updates_ = true;
666  initialized_ = false;
667 }
668 
669 void
671 {
672  stop_updates_ = false;
673 
674  // block until the costmap is re-initialized.. meaning one update cycle has run
675  rclcpp::Rate r(100.0);
676  while (!initialized_) {
677  r.sleep();
678  }
679 }
680 
681 void
683 {
684  Costmap2D * top = layered_costmap_->getCostmap();
685  top->resetMap(0, 0, top->getSizeInCellsX(), top->getSizeInCellsY());
686 
687  // Reset each of the plugins
688  std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
689  std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
690  for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
691  plugin != plugins->end(); ++plugin)
692  {
693  (*plugin)->reset();
694  }
695  for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
696  filter != filters->end(); ++filter)
697  {
698  (*filter)->reset();
699  }
700 }
701 
702 bool
703 Costmap2DROS::getRobotPose(geometry_msgs::msg::PoseStamped & global_pose)
704 {
705  return nav2_util::getCurrentPose(
706  global_pose, *tf_buffer_,
708 }
709 
710 bool
712  const geometry_msgs::msg::PoseStamped & input_pose,
713  geometry_msgs::msg::PoseStamped & transformed_pose)
714 {
715  if (input_pose.header.frame_id == global_frame_) {
716  transformed_pose = input_pose;
717  return true;
718  } else {
719  return nav2_util::transformPoseInTargetFrame(
720  input_pose, transformed_pose, *tf_buffer_,
722  }
723 }
724 
725 rcl_interfaces::msg::SetParametersResult
726 Costmap2DROS::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
727 {
728  auto result = rcl_interfaces::msg::SetParametersResult();
729  bool resize_map = false;
730  std::lock_guard<std::mutex> lock_reinit(_dynamic_parameter_mutex);
731 
732  for (auto parameter : parameters) {
733  const auto & type = parameter.get_type();
734  const auto & name = parameter.get_name();
735 
736  if (type == ParameterType::PARAMETER_DOUBLE) {
737  if (name == "robot_radius") {
738  robot_radius_ = parameter.as_double();
739  // Set the footprint
740  if (use_radius_) {
742  }
743  } else if (name == "footprint_padding") {
744  footprint_padding_ = parameter.as_double();
745  padded_footprint_ = unpadded_footprint_;
746  padFootprint(padded_footprint_, footprint_padding_);
747  layered_costmap_->setFootprint(padded_footprint_);
748  } else if (name == "transform_tolerance") {
749  transform_tolerance_ = parameter.as_double();
750  } else if (name == "publish_frequency") {
751  map_publish_frequency_ = parameter.as_double();
752  if (map_publish_frequency_ > 0) {
753  publish_cycle_ = rclcpp::Duration::from_seconds(1 / map_publish_frequency_);
754  } else {
755  publish_cycle_ = rclcpp::Duration(-1s);
756  }
757  } else if (name == "resolution") {
758  resize_map = true;
759  resolution_ = parameter.as_double();
760  } else if (name == "origin_x") {
761  resize_map = true;
762  origin_x_ = parameter.as_double();
763  } else if (name == "origin_y") {
764  resize_map = true;
765  origin_y_ = parameter.as_double();
766  }
767  } else if (type == ParameterType::PARAMETER_INTEGER) {
768  if (name == "width") {
769  if (parameter.as_int() > 0) {
770  resize_map = true;
771  map_width_meters_ = parameter.as_int();
772  } else {
773  RCLCPP_ERROR(
774  get_logger(), "You try to set width of map to be negative or zero,"
775  " this isn't allowed, please give a positive value.");
776  result.successful = false;
777  return result;
778  }
779  } else if (name == "height") {
780  if (parameter.as_int() > 0) {
781  resize_map = true;
782  map_height_meters_ = parameter.as_int();
783  } else {
784  RCLCPP_ERROR(
785  get_logger(), "You try to set height of map to be negative or zero,"
786  " this isn't allowed, please give a positive value.");
787  result.successful = false;
788  return result;
789  }
790  }
791  } else if (type == ParameterType::PARAMETER_STRING) {
792  if (name == "footprint") {
793  footprint_ = parameter.as_string();
794  std::vector<geometry_msgs::msg::Point> new_footprint;
795  if (makeFootprintFromString(footprint_, new_footprint)) {
796  setRobotFootprint(new_footprint);
797  }
798  } else if (name == "robot_base_frame") {
799  // First, make sure that the transform between the robot base frame
800  // and the global frame is available
801  std::string tf_error;
802  RCLCPP_INFO(get_logger(), "Checking transform");
803  if (!tf_buffer_->canTransform(
804  global_frame_, parameter.as_string(), tf2::TimePointZero,
805  tf2::durationFromSec(1.0), &tf_error))
806  {
807  RCLCPP_WARN(
808  get_logger(), "Timed out waiting for transform from %s to %s"
809  " to become available, tf error: %s",
810  parameter.as_string().c_str(), global_frame_.c_str(), tf_error.c_str());
811  RCLCPP_WARN(
812  get_logger(), "Rejecting robot_base_frame change to %s , leaving it to its original"
813  " value of %s", parameter.as_string().c_str(), robot_base_frame_.c_str());
814  result.successful = false;
815  return result;
816  }
817  robot_base_frame_ = parameter.as_string();
818  }
819  }
820  }
821 
822  if (resize_map && !layered_costmap_->isSizeLocked()) {
823  layered_costmap_->resizeMap(
824  (unsigned int)(map_width_meters_ / resolution_),
825  (unsigned int)(map_height_meters_ / resolution_), resolution_, origin_x_, origin_y_);
826  updateMap();
827  }
828 
829  result.successful = true;
830  return result;
831 }
832 
834  const std::shared_ptr<rmw_request_id_t>,
835  const std::shared_ptr<nav2_msgs::srv::GetCost::Request> request,
836  const std::shared_ptr<nav2_msgs::srv::GetCost::Response> response)
837 {
838  unsigned int mx, my;
839 
840  Costmap2D * costmap = layered_costmap_->getCostmap();
841 
842  if (request->use_footprint) {
843  Footprint footprint = layered_costmap_->getFootprint();
844  FootprintCollisionChecker<Costmap2D *> collision_checker(costmap);
845 
846  RCLCPP_INFO(
847  get_logger(), "Received request to get cost at footprint pose (%.2f, %.2f, %.2f)",
848  request->x, request->y, request->theta);
849 
850  response->cost = collision_checker.footprintCostAtPose(
851  request->x, request->y, request->theta, footprint);
852  } else if (costmap->worldToMap(request->x, request->y, mx, my)) {
853  RCLCPP_INFO(
854  get_logger(), "Received request to get cost at point (%f, %f)", request->x, request->y);
855 
856  // Get the cost at the map coordinates
857  response->cost = static_cast<float>(costmap->getCost(mx, my));
858  } else {
859  RCLCPP_WARN(get_logger(), "Point (%f, %f) is out of bounds", request->x, request->y);
860  response->cost = -1.0;
861  }
862 }
863 
864 } // 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
std::string getName() const
Returns costmap name.
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.
double map_vis_z_
The height of map, allows to avoid flickering at -0.008.
double initial_transform_timeout_
The timeout before activation of the node errors.
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 getCostCallback(const std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< nav2_msgs::srv::GetCost::Request > request, const std::shared_ptr< nav2_msgs::srv::GetCost::Response > response)
Get the cost at a point in 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.
void init()
Common initialization for constructors.
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 char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:264
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:285
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:514
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:519
Checker for collision with a footprint on a costmap.
double footprintCostAtPose(double x, double y, double theta, const Footprint &footprint)
Find the footprint cost a a post with an unoriented footprint.
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:110
bool makeFootprintFromString(const std::string &footprint_string, std::vector< geometry_msgs::msg::Point > &footprint)
Make the footprint from the given string.
Definition: footprint.cpp:175
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:145
std::vector< geometry_msgs::msg::Point > makeFootprintFromRadius(double radius)
Create a circular footprint from a given radius.
Definition: footprint.cpp:156
std::vector< geometry_msgs::msg::Point > toPointVector(geometry_msgs::msg::Polygon::SharedPtr polygon)
Convert Polygon msg to vector of Points.
Definition: footprint.cpp:101