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,
const bool & use_sim_time)
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"}
73 declare_parameter(
"map_topic", rclcpp::ParameterValue(std::string(
"map")));
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,
"",
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"),
95 parent_namespace_(parent_namespace),
96 default_plugins_{
"static_layer",
"obstacle_layer",
"inflation_layer"},
98 "nav2_costmap_2d::StaticLayer",
99 "nav2_costmap_2d::ObstacleLayer",
100 "nav2_costmap_2d::InflationLayer"}
103 "map_topic", rclcpp::ParameterValue(
104 (parent_namespace_ ==
"/" ?
"/" : parent_namespace_ +
"/") + std::string(
"map")));
110 RCLCPP_INFO(get_logger(),
"Creating Costmap");
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));
143 nav2_util::CallbackReturn
146 RCLCPP_INFO(get_logger(),
"Configuring");
149 }
catch (
const std::exception & e) {
151 get_logger(),
"Failed to configure costmap! %s.", e.what());
152 return nav2_util::CallbackReturn::FAILURE;
155 callback_group_ = create_callback_group(
156 rclcpp::CallbackGroupType::MutuallyExclusive,
false);
159 layered_costmap_ = std::make_unique<LayeredCostmap>(
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_);
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(),
174 tf_buffer_->setCreateTimerInterface(timer_interface);
175 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
178 for (
unsigned int i = 0; i < plugin_names_.size(); ++i) {
179 RCLCPP_INFO(get_logger(),
"Using plugin \"%s\"", plugin_names_[i].c_str());
181 std::shared_ptr<Layer> plugin = plugin_loader_.createSharedInstance(plugin_types_[i]);
184 std::unique_lock<Costmap2D::mutex_t> lock(*(layered_costmap_->getCostmap()->getMutex()));
186 layered_costmap_->addPlugin(plugin);
190 plugin->initialize(layered_costmap_.get(), plugin_names_[i], tf_buffer_.get(),
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;
200 RCLCPP_INFO(get_logger(),
"Initialized plugin \"%s\"", plugin_names_[i].c_str());
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());
206 std::shared_ptr<Layer> filter = plugin_loader_.createSharedInstance(filter_types_[i]);
209 std::unique_lock<Costmap2D::mutex_t> lock(*(layered_costmap_->getCostmap()->getMutex()));
211 layered_costmap_->addFilter(filter);
214 layered_costmap_.get(), filter_names_[i], tf_buffer_.get(),
219 RCLCPP_INFO(get_logger(),
"Initialized costmap filter \"%s\"", filter_names_[i].c_str());
223 footprint_sub_ = create_subscription<geometry_msgs::msg::Polygon>(
225 rclcpp::SystemDefaultsQoS(),
228 footprint_pub_ = create_publisher<geometry_msgs::msg::PolygonStamped>(
229 "published_footprint", rclcpp::SystemDefaultsQoS());
231 costmap_publisher_ = std::make_unique<Costmap2DPublisher>(
234 "costmap", always_send_full_costmap_,
map_vis_z_);
236 auto layers = layered_costmap_->getPlugins();
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>(
245 layer->getName(), always_send_full_costmap_,
map_vis_z_)
254 std::vector<geometry_msgs::msg::Point> new_footprint;
260 get_cost_service_ = create_service<nav2_msgs::srv::GetCost>(
263 std::placeholders::_3));
266 clear_costmap_service_ = std::make_unique<ClearCostmapService>(
shared_from_this(), *
this);
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;
274 nav2_util::CallbackReturn
277 RCLCPP_INFO(get_logger(),
"Activating");
282 std::string tf_error;
284 RCLCPP_INFO(get_logger(),
"Checking transform");
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(
294 get_logger(),
"Timed out waiting for transform from %s to %s"
295 " to become available, tf error: %s",
299 if (now() > initial_transform_timeout_point) {
302 "Failed to activate %s because "
303 "transform from %s to %s did not become available before timeout",
306 return nav2_util::CallbackReturn::FAILURE;
316 footprint_pub_->on_activate();
317 costmap_publisher_->on_activate();
319 for (
auto & layer_pub : layer_publishers_) {
320 layer_pub->on_activate();
325 stop_updates_ =
false;
326 map_update_thread_shutdown_ =
false;
333 dyn_params_handler = this->add_on_set_parameters_callback(
336 return nav2_util::CallbackReturn::SUCCESS;
339 nav2_util::CallbackReturn
342 RCLCPP_INFO(get_logger(),
"Deactivating");
344 remove_on_set_parameters_callback(dyn_params_handler.get());
345 dyn_params_handler.reset();
350 map_update_thread_shutdown_ =
true;
356 footprint_pub_->on_deactivate();
357 costmap_publisher_->on_deactivate();
359 for (
auto & layer_pub : layer_publishers_) {
360 layer_pub->on_deactivate();
363 return nav2_util::CallbackReturn::SUCCESS;
366 nav2_util::CallbackReturn
369 RCLCPP_INFO(get_logger(),
"Cleaning up");
370 executor_thread_.reset();
372 costmap_publisher_.reset();
373 clear_costmap_service_.reset();
375 layer_publishers_.clear();
377 layered_costmap_.reset();
379 tf_listener_.reset();
382 footprint_sub_.reset();
383 footprint_pub_.reset();
385 return nav2_util::CallbackReturn::SUCCESS;
388 nav2_util::CallbackReturn
391 RCLCPP_INFO(get_logger(),
"Shutting down");
392 return nav2_util::CallbackReturn::SUCCESS;
398 RCLCPP_DEBUG(get_logger(),
" getParameters");
401 get_parameter(
"always_send_full_costmap", always_send_full_costmap_);
403 get_parameter(
"footprint", footprint_);
404 get_parameter(
"footprint_padding", footprint_padding_);
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_);
412 get_parameter(
"robot_radius", robot_radius_);
414 get_parameter(
"track_unknown_space", track_unknown_space_);
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_);
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]));
430 plugin_types_.resize(plugin_names_.size());
431 filter_types_.resize(filter_names_.size());
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]);
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]);
442 if (map_publish_frequency_ > 0) {
443 publish_cycle_ = rclcpp::Duration::from_seconds(1 / map_publish_frequency_);
445 publish_cycle_ = rclcpp::Duration(-1s);
451 if (footprint_ !=
"" && footprint_ !=
"[]") {
453 std::vector<geometry_msgs::msg::Point> new_footprint;
460 get_logger(),
"The footprint parameter is invalid: \"%s\", using radius (%lf) instead",
461 footprint_.c_str(), robot_radius_);
466 if (map_width_meters_ <= 0) {
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.");
471 if (map_height_meters_ <= 0) {
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.");
481 unpadded_footprint_ = points;
482 padded_footprint_ = points;
484 layered_costmap_->setFootprint(padded_footprint_);
489 const geometry_msgs::msg::Polygon::SharedPtr footprint)
497 geometry_msgs::msg::PoseStamped global_pose;
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);
511 RCLCPP_DEBUG(get_logger(),
"mapUpdateLoop frequency: %lf", frequency);
514 if (frequency == 0.0) {
518 RCLCPP_DEBUG(get_logger(),
"Entering loop");
520 rclcpp::WallRate r(frequency);
522 while (rclcpp::ok() && !map_update_thread_shutdown_) {
528 std::scoped_lock<std::mutex> lock(_dynamic_parameter_mutex);
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);
541 for (
auto & layer_pub : layer_publishers_) {
542 layer_pub->updateBounds(x0, xn, y0, yn);
545 auto current_time = now();
546 if ((last_publish_ + publish_cycle_ < current_time) ||
550 RCLCPP_DEBUG(get_logger(),
"Publish costmap at %s", name_.c_str());
551 costmap_publisher_->publishCostmap();
553 for (
auto & layer_pub : layer_publishers_) {
554 layer_pub->publishCostmap();
557 last_publish_ = current_time;
567 if (r.period() > tf2::durationFromSec(1 / frequency)) {
570 "Costmap2DROS: Map update loop missed its desired rate of %.4fHz... "
571 "the loop actually took %.4f seconds", frequency, r.period());
580 RCLCPP_DEBUG(get_logger(),
"Updating map...");
582 if (!stop_updates_) {
584 geometry_msgs::msg::PoseStamped 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);
591 auto footprint = std::make_unique<geometry_msgs::msg::PolygonStamped>();
592 footprint->header = pose.header;
595 RCLCPP_DEBUG(get_logger(),
"Publishing footprint");
596 footprint_pub_->publish(std::move(footprint));
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();
612 for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
613 plugin != plugins->end();
616 (*plugin)->activate();
618 for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
619 filter != filters->end();
622 (*filter)->activate();
626 stop_updates_ =
false;
629 rclcpp::Rate r(20.0);
630 while (rclcpp::ok() && !initialized_) {
631 RCLCPP_DEBUG(get_logger(),
"Sleeping, waiting for initialized_");
639 stop_updates_ =
true;
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();
647 for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
648 plugin != plugins->end(); ++plugin)
650 (*plugin)->deactivate();
652 for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
653 filter != filters->end(); ++filter)
655 (*filter)->deactivate();
658 initialized_ =
false;
665 stop_updates_ =
true;
666 initialized_ =
false;
672 stop_updates_ =
false;
675 rclcpp::Rate r(100.0);
676 while (!initialized_) {
684 Costmap2D * top = layered_costmap_->getCostmap();
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)
695 for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
696 filter != filters->end(); ++filter)
705 return nav2_util::getCurrentPose(
706 global_pose, *tf_buffer_,
712 const geometry_msgs::msg::PoseStamped & input_pose,
713 geometry_msgs::msg::PoseStamped & transformed_pose)
716 transformed_pose = input_pose;
719 return nav2_util::transformPoseInTargetFrame(
720 input_pose, transformed_pose, *tf_buffer_,
725 rcl_interfaces::msg::SetParametersResult
728 auto result = rcl_interfaces::msg::SetParametersResult();
729 bool resize_map =
false;
730 std::lock_guard<std::mutex> lock_reinit(_dynamic_parameter_mutex);
732 for (
auto parameter : parameters) {
733 const auto & type = parameter.get_type();
734 const auto & name = parameter.get_name();
736 if (type == ParameterType::PARAMETER_DOUBLE) {
737 if (name ==
"robot_radius") {
738 robot_radius_ = parameter.as_double();
743 }
else if (name ==
"footprint_padding") {
744 footprint_padding_ = parameter.as_double();
745 padded_footprint_ = unpadded_footprint_;
747 layered_costmap_->setFootprint(padded_footprint_);
748 }
else if (name ==
"transform_tolerance") {
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_);
755 publish_cycle_ = rclcpp::Duration(-1s);
757 }
else if (name ==
"resolution") {
759 resolution_ = parameter.as_double();
760 }
else if (name ==
"origin_x") {
762 origin_x_ = parameter.as_double();
763 }
else if (name ==
"origin_y") {
765 origin_y_ = parameter.as_double();
767 }
else if (type == ParameterType::PARAMETER_INTEGER) {
768 if (name ==
"width") {
769 if (parameter.as_int() > 0) {
771 map_width_meters_ = parameter.as_int();
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;
779 }
else if (name ==
"height") {
780 if (parameter.as_int() > 0) {
782 map_height_meters_ = parameter.as_int();
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;
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;
798 }
else if (name ==
"robot_base_frame") {
801 std::string tf_error;
802 RCLCPP_INFO(get_logger(),
"Checking transform");
803 if (!tf_buffer_->canTransform(
805 tf2::durationFromSec(1.0), &tf_error))
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());
812 get_logger(),
"Rejecting robot_base_frame change to %s , leaving it to its original"
814 result.successful =
false;
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_);
829 result.successful =
true;
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)
840 Costmap2D * costmap = layered_costmap_->getCostmap();
842 if (request->use_footprint) {
843 Footprint footprint = layered_costmap_->getFootprint();
847 get_logger(),
"Received request to get cost at footprint pose (%.2f, %.2f, %.2f)",
848 request->x, request->y, request->theta);
851 request->x, request->y, request->theta, footprint);
852 }
else if (costmap->
worldToMap(request->x, request->y, mx, my)) {
854 get_logger(),
"Received request to get cost at point (%f, %f)", request->x, request->y);
857 response->cost =
static_cast<float>(costmap->
getCost(mx, my));
859 RCLCPP_WARN(get_logger(),
"Point (%f, %f) is out of bounds", request->x, request->y);
860 response->cost = -1.0;
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.
~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.
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".
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
Reset the costmap in bounds.
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
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.