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