39 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
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"
55 using namespace std::chrono_literals;
56 using std::placeholders::_1;
57 using rcl_interfaces::msg::ParameterType;
61 Costmap2DROS::Costmap2DROS(
const std::string & name)
65 : nav2_util::LifecycleNode(
"costmap",
"", options),
67 default_plugins_{
"static_layer",
"obstacle_layer",
"inflation_layer"},
69 "nav2_costmap_2d::StaticLayer",
70 "nav2_costmap_2d::ObstacleLayer",
71 "nav2_costmap_2d::InflationLayer"}
75 RCLCPP_INFO(get_logger(),
"Creating Costmap");
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));
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));
106 const std::string & name,
107 const std::string & parent_namespace,
108 const std::string & local_namespace)
109 : nav2_util::LifecycleNode(name,
"",
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
120 parent_namespace_(parent_namespace),
121 default_plugins_{
"static_layer",
"obstacle_layer",
"inflation_layer"},
123 "nav2_costmap_2d::StaticLayer",
124 "nav2_costmap_2d::ObstacleLayer",
125 "nav2_costmap_2d::InflationLayer"}
127 RCLCPP_INFO(get_logger(),
"Creating Costmap");
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));
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));
161 nav2_util::CallbackReturn
164 RCLCPP_INFO(get_logger(),
"Configuring");
167 callback_group_ = create_callback_group(
168 rclcpp::CallbackGroupType::MutuallyExclusive,
false);
171 layered_costmap_ = std::make_unique<LayeredCostmap>(
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_);
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(),
186 tf_buffer_->setCreateTimerInterface(timer_interface);
187 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
190 for (
unsigned int i = 0; i < plugin_names_.size(); ++i) {
191 RCLCPP_INFO(get_logger(),
"Using plugin \"%s\"", plugin_names_[i].c_str());
193 std::shared_ptr<Layer> plugin = plugin_loader_.createSharedInstance(plugin_types_[i]);
196 std::unique_lock<Costmap2D::mutex_t> lock(*(layered_costmap_->getCostmap()->getMutex()));
198 layered_costmap_->addPlugin(plugin);
202 layered_costmap_.get(), plugin_names_[i], tf_buffer_.get(),
207 RCLCPP_INFO(get_logger(),
"Initialized plugin \"%s\"", plugin_names_[i].c_str());
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());
213 std::shared_ptr<Layer> filter = plugin_loader_.createSharedInstance(filter_types_[i]);
216 std::unique_lock<Costmap2D::mutex_t> lock(*(layered_costmap_->getCostmap()->getMutex()));
218 layered_costmap_->addFilter(filter);
221 layered_costmap_.get(), filter_names_[i], tf_buffer_.get(),
226 RCLCPP_INFO(get_logger(),
"Initialized costmap filter \"%s\"", filter_names_[i].c_str());
230 footprint_sub_ = create_subscription<geometry_msgs::msg::Polygon>(
232 rclcpp::SystemDefaultsQoS(),
235 footprint_pub_ = create_publisher<geometry_msgs::msg::PolygonStamped>(
236 "published_footprint", rclcpp::SystemDefaultsQoS());
238 costmap_publisher_ = std::make_unique<Costmap2DPublisher>(
241 "costmap", always_send_full_costmap_);
247 std::vector<geometry_msgs::msg::Point> new_footprint;
253 clear_costmap_service_ = std::make_unique<ClearCostmapService>(
shared_from_this(), *
this);
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;
261 nav2_util::CallbackReturn
264 RCLCPP_INFO(get_logger(),
"Activating");
266 costmap_publisher_->on_activate();
267 footprint_pub_->on_activate();
272 std::string tf_error;
274 RCLCPP_INFO(get_logger(),
"Checking transform");
276 while (rclcpp::ok() &&
277 !tf_buffer_->canTransform(
281 get_logger(),
"Timed out waiting for transform from %s to %s"
282 " to become available, tf error: %s",
293 stop_updates_ =
false;
294 map_update_thread_shutdown_ =
false;
301 dyn_params_handler = this->add_on_set_parameters_callback(
304 return nav2_util::CallbackReturn::SUCCESS;
307 nav2_util::CallbackReturn
310 RCLCPP_INFO(get_logger(),
"Deactivating");
312 dyn_params_handler.reset();
317 map_update_thread_shutdown_ =
true;
323 costmap_publisher_->on_deactivate();
324 footprint_pub_->on_deactivate();
326 return nav2_util::CallbackReturn::SUCCESS;
329 nav2_util::CallbackReturn
332 RCLCPP_INFO(get_logger(),
"Cleaning up");
334 layered_costmap_.reset();
336 tf_listener_.reset();
339 footprint_sub_.reset();
340 footprint_pub_.reset();
342 costmap_publisher_.reset();
343 clear_costmap_service_.reset();
345 executor_thread_.reset();
346 return nav2_util::CallbackReturn::SUCCESS;
349 nav2_util::CallbackReturn
352 RCLCPP_INFO(get_logger(),
"Shutting down");
353 return nav2_util::CallbackReturn::SUCCESS;
359 RCLCPP_DEBUG(get_logger(),
" getParameters");
362 get_parameter(
"always_send_full_costmap", always_send_full_costmap_);
363 get_parameter(
"footprint", footprint_);
364 get_parameter(
"footprint_padding", footprint_padding_);
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_);
372 get_parameter(
"robot_radius", robot_radius_);
374 get_parameter(
"track_unknown_space", track_unknown_space_);
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_);
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]));
389 plugin_types_.resize(plugin_names_.size());
390 filter_types_.resize(filter_names_.size());
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]);
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]);
401 if (map_publish_frequency_ > 0) {
402 publish_cycle_ = rclcpp::Duration::from_seconds(1 / map_publish_frequency_);
404 publish_cycle_ = rclcpp::Duration(-1s);
410 if (footprint_ !=
"" && footprint_ !=
"[]") {
412 std::vector<geometry_msgs::msg::Point> new_footprint;
419 get_logger(),
"The footprint parameter is invalid: \"%s\", using radius (%lf) instead",
420 footprint_.c_str(), robot_radius_);
428 unpadded_footprint_ = points;
429 padded_footprint_ = points;
431 layered_costmap_->setFootprint(padded_footprint_);
436 const geometry_msgs::msg::Polygon::SharedPtr footprint)
444 geometry_msgs::msg::PoseStamped global_pose;
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);
458 RCLCPP_DEBUG(get_logger(),
"mapUpdateLoop frequency: %lf", frequency);
461 if (frequency == 0.0) {
465 RCLCPP_DEBUG(get_logger(),
"Entering loop");
467 rclcpp::WallRate r(frequency);
469 while (rclcpp::ok() && !map_update_thread_shutdown_) {
475 std::scoped_lock<std::mutex> lock(_dynamic_parameter_mutex);
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);
488 auto current_time = now();
489 if ((last_publish_ + publish_cycle_ < current_time) ||
490 (current_time < last_publish_))
492 RCLCPP_DEBUG(get_logger(),
"Publish costmap at %s", name_.c_str());
493 costmap_publisher_->publishCostmap();
494 last_publish_ = current_time;
504 if (r.period() > tf2::durationFromSec(1 / frequency)) {
507 "Costmap2DROS: Map update loop missed its desired rate of %.4fHz... "
508 "the loop actually took %.4f seconds", frequency, r.period());
517 RCLCPP_DEBUG(get_logger(),
"Updating map...");
519 if (!stop_updates_) {
521 geometry_msgs::msg::PoseStamped 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);
528 auto footprint = std::make_unique<geometry_msgs::msg::PolygonStamped>();
529 footprint->header = pose.header;
532 RCLCPP_DEBUG(get_logger(),
"Publishing footprint");
533 footprint_pub_->publish(std::move(footprint));
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();
549 for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
550 plugin != plugins->end();
553 (*plugin)->activate();
555 for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
556 filter != filters->end();
559 (*filter)->activate();
563 stop_updates_ =
false;
566 rclcpp::Rate r(20.0);
567 while (rclcpp::ok() && !initialized_) {
568 RCLCPP_DEBUG(get_logger(),
"Sleeping, waiting for initialized_");
576 stop_updates_ =
true;
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();
583 for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
584 plugin != plugins->end(); ++plugin)
586 (*plugin)->deactivate();
588 for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
589 filter != filters->end(); ++filter)
591 (*filter)->deactivate();
594 initialized_ =
false;
601 stop_updates_ =
true;
602 initialized_ =
false;
608 stop_updates_ =
false;
611 rclcpp::Rate r(100.0);
612 while (!initialized_) {
620 Costmap2D * top = layered_costmap_->getCostmap();
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)
631 for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
632 filter != filters->end(); ++filter)
641 return nav2_util::getCurrentPose(
642 global_pose, *tf_buffer_,
648 const geometry_msgs::msg::PoseStamped & input_pose,
649 geometry_msgs::msg::PoseStamped & transformed_pose)
652 transformed_pose = input_pose;
655 return nav2_util::transformPoseInTargetFrame(
656 input_pose, transformed_pose, *tf_buffer_,
661 rcl_interfaces::msg::SetParametersResult
664 auto result = rcl_interfaces::msg::SetParametersResult();
665 bool resize_map =
false;
666 std::lock_guard<std::mutex> lock_reinit(_dynamic_parameter_mutex);
668 for (
auto parameter : parameters) {
669 const auto & type = parameter.get_type();
670 const auto & name = parameter.get_name();
672 if (type == ParameterType::PARAMETER_DOUBLE) {
673 if (name ==
"robot_radius") {
674 robot_radius_ = parameter.as_double();
679 }
else if (name ==
"footprint_padding") {
680 footprint_padding_ = parameter.as_double();
681 padded_footprint_ = unpadded_footprint_;
683 layered_costmap_->setFootprint(padded_footprint_);
684 }
else if (name ==
"transform_tolerance") {
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_);
691 publish_cycle_ = rclcpp::Duration(-1s);
693 }
else if (name ==
"resolution") {
695 resolution_ = parameter.as_double();
696 }
else if (name ==
"origin_x") {
698 origin_x_ = parameter.as_double();
699 }
else if (name ==
"origin_y") {
701 origin_y_ = parameter.as_double();
703 }
else if (type == ParameterType::PARAMETER_INTEGER) {
704 if (name ==
"width") {
705 if (parameter.as_int() > 0) {
707 map_width_meters_ = parameter.as_int();
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;
715 }
else if (name ==
"height") {
716 if (parameter.as_int() > 0) {
718 map_height_meters_ = parameter.as_int();
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;
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;
734 }
else if (name ==
"robot_base_frame") {
737 std::string tf_error;
738 RCLCPP_INFO(get_logger(),
"Checking transform");
739 if (!tf_buffer_->canTransform(
741 tf2::durationFromSec(1.0), &tf_error))
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());
748 get_logger(),
"Rejecting robot_base_frame change to %s , leaving it to its original"
750 result.successful =
false;
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_);
765 result.successful =
true;
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
~Costmap2DROS()
A destructor.
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".
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
Reset the costmap in bounds.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
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)
bool makeFootprintFromString(const std::string &footprint_string, std::vector< geometry_msgs::msg::Point > &footprint)
Make the footprint from the given string.
void padFootprint(std::vector< geometry_msgs::msg::Point > &footprint, double padding)
Adds the specified amount of padding to the footprint (in place)
std::vector< geometry_msgs::msg::Point > makeFootprintFromRadius(double radius)
Create a circular footprint from a given radius.
std::vector< geometry_msgs::msg::Point > toPointVector(geometry_msgs::msg::Polygon::SharedPtr polygon)
Convert Polygon msg to vector of Points.