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 rclcpp::NodeOptions & options)
62 : nav2_util::LifecycleNode(
"costmap",
"", options),
64 default_plugins_{
"static_layer",
"obstacle_layer",
"inflation_layer"},
66 "nav2_costmap_2d::StaticLayer",
67 "nav2_costmap_2d::ObstacleLayer",
68 "nav2_costmap_2d::InflationLayer"}
75 const std::string & name,
76 const std::string & parent_namespace,
77 const bool & use_sim_time)
78 : nav2_util::LifecycleNode(name,
"",
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"),
90 default_plugins_{
"static_layer",
"obstacle_layer",
"inflation_layer"},
92 "nav2_costmap_2d::StaticLayer",
93 "nav2_costmap_2d::ObstacleLayer",
94 "nav2_costmap_2d::InflationLayer"}
101 RCLCPP_INFO(get_logger(),
"Creating Costmap");
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));
134 nav2_util::CallbackReturn
137 RCLCPP_INFO(get_logger(),
"Configuring");
140 }
catch (
const std::exception & e) {
142 get_logger(),
"Failed to configure costmap! %s.", e.what());
143 return nav2_util::CallbackReturn::FAILURE;
146 callback_group_ = create_callback_group(
147 rclcpp::CallbackGroupType::MutuallyExclusive,
false);
150 layered_costmap_ = std::make_unique<LayeredCostmap>(
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_);
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(),
165 tf_buffer_->setCreateTimerInterface(timer_interface);
166 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
169 for (
unsigned int i = 0; i < plugin_names_.size(); ++i) {
170 RCLCPP_INFO(get_logger(),
"Using plugin \"%s\"", plugin_names_[i].c_str());
172 std::shared_ptr<Layer> plugin = plugin_loader_.createSharedInstance(plugin_types_[i]);
175 std::unique_lock<Costmap2D::mutex_t> lock(*(layered_costmap_->getCostmap()->getMutex()));
177 layered_costmap_->addPlugin(plugin);
181 plugin->initialize(layered_costmap_.get(), plugin_names_[i], tf_buffer_.get(),
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;
191 RCLCPP_INFO(get_logger(),
"Initialized plugin \"%s\"", plugin_names_[i].c_str());
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());
197 std::shared_ptr<Layer> filter = plugin_loader_.createSharedInstance(filter_types_[i]);
200 std::unique_lock<Costmap2D::mutex_t> lock(*(layered_costmap_->getCostmap()->getMutex()));
202 layered_costmap_->addFilter(filter);
205 layered_costmap_.get(), filter_names_[i], tf_buffer_.get(),
210 RCLCPP_INFO(get_logger(),
"Initialized costmap filter \"%s\"", filter_names_[i].c_str());
214 footprint_sub_ = create_subscription<geometry_msgs::msg::Polygon>(
216 rclcpp::SystemDefaultsQoS(),
219 footprint_pub_ = create_publisher<geometry_msgs::msg::PolygonStamped>(
220 "published_footprint", rclcpp::SystemDefaultsQoS());
222 costmap_publisher_ = std::make_unique<Costmap2DPublisher>(
225 "costmap", always_send_full_costmap_,
map_vis_z_);
227 auto layers = layered_costmap_->getPlugins();
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>(
236 layer->getName(), always_send_full_costmap_,
map_vis_z_)
245 std::vector<geometry_msgs::msg::Point> new_footprint;
252 std::shared_ptr<nav2_util::LifecycleNode>>>(
253 std::string(
"get_cost_") + get_name(),
256 std::placeholders::_3));
259 clear_costmap_service_ = std::make_unique<ClearCostmapService>(
shared_from_this(), *
this);
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;
267 nav2_util::CallbackReturn
270 RCLCPP_INFO(get_logger(),
"Activating");
275 std::string tf_error;
277 RCLCPP_INFO(get_logger(),
"Checking transform");
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(
287 get_logger(),
"Timed out waiting for transform from %s to %s"
288 " to become available, tf error: %s",
292 if (now() > initial_transform_timeout_point) {
295 "Failed to activate %s because "
296 "transform from %s to %s did not become available before timeout",
299 return nav2_util::CallbackReturn::FAILURE;
309 footprint_pub_->on_activate();
310 costmap_publisher_->on_activate();
312 for (
auto & layer_pub : layer_publishers_) {
313 layer_pub->on_activate();
318 stop_updates_ =
false;
319 map_update_thread_shutdown_ =
false;
326 dyn_params_handler = this->add_on_set_parameters_callback(
329 return nav2_util::CallbackReturn::SUCCESS;
332 nav2_util::CallbackReturn
335 RCLCPP_INFO(get_logger(),
"Deactivating");
337 remove_on_set_parameters_callback(dyn_params_handler.get());
338 dyn_params_handler.reset();
343 map_update_thread_shutdown_ =
true;
349 footprint_pub_->on_deactivate();
350 costmap_publisher_->on_deactivate();
352 for (
auto & layer_pub : layer_publishers_) {
353 layer_pub->on_deactivate();
356 return nav2_util::CallbackReturn::SUCCESS;
359 nav2_util::CallbackReturn
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();
368 layer_publishers_.clear();
370 layered_costmap_.reset();
372 tf_listener_.reset();
375 footprint_sub_.reset();
376 footprint_pub_.reset();
378 return nav2_util::CallbackReturn::SUCCESS;
381 nav2_util::CallbackReturn
384 RCLCPP_INFO(get_logger(),
"Shutting down");
385 return nav2_util::CallbackReturn::SUCCESS;
391 RCLCPP_DEBUG(get_logger(),
" getParameters");
394 get_parameter(
"always_send_full_costmap", always_send_full_costmap_);
396 get_parameter(
"footprint", footprint_);
397 get_parameter(
"footprint_padding", footprint_padding_);
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_);
405 get_parameter(
"robot_radius", robot_radius_);
407 get_parameter(
"track_unknown_space", track_unknown_space_);
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_);
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]));
423 plugin_types_.resize(plugin_names_.size());
424 filter_types_.resize(filter_names_.size());
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]);
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]);
435 if (map_publish_frequency_ > 0) {
436 publish_cycle_ = rclcpp::Duration::from_seconds(1 / map_publish_frequency_);
438 publish_cycle_ = rclcpp::Duration(-1s);
444 if (footprint_ !=
"" && footprint_ !=
"[]") {
446 std::vector<geometry_msgs::msg::Point> new_footprint;
453 get_logger(),
"The footprint parameter is invalid: \"%s\", using radius (%lf) instead",
454 footprint_.c_str(), robot_radius_);
459 if (map_width_meters_ <= 0) {
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.");
464 if (map_height_meters_ <= 0) {
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.");
474 unpadded_footprint_ = points;
475 padded_footprint_ = points;
477 layered_costmap_->setFootprint(padded_footprint_);
482 const geometry_msgs::msg::Polygon::SharedPtr footprint)
490 geometry_msgs::msg::PoseStamped global_pose;
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);
504 RCLCPP_DEBUG(get_logger(),
"mapUpdateLoop frequency: %lf", frequency);
507 if (frequency == 0.0) {
511 RCLCPP_DEBUG(get_logger(),
"Entering loop");
513 rclcpp::WallRate r(frequency);
515 while (rclcpp::ok() && !map_update_thread_shutdown_) {
521 std::scoped_lock<std::mutex> lock(_dynamic_parameter_mutex);
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);
534 for (
auto & layer_pub : layer_publishers_) {
535 layer_pub->updateBounds(x0, xn, y0, yn);
538 auto current_time = now();
539 if ((last_publish_ + publish_cycle_ < current_time) ||
543 RCLCPP_DEBUG(get_logger(),
"Publish costmap at %s", name_.c_str());
544 costmap_publisher_->publishCostmap();
546 for (
auto & layer_pub : layer_publishers_) {
547 layer_pub->publishCostmap();
550 last_publish_ = current_time;
560 if (r.period() > tf2::durationFromSec(1 / frequency)) {
563 "Costmap2DROS: Map update loop missed its desired rate of %.4fHz... "
564 "the loop actually took %.4f seconds", frequency, r.period());
573 RCLCPP_DEBUG(get_logger(),
"Updating map...");
575 if (!stop_updates_) {
577 geometry_msgs::msg::PoseStamped 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);
584 auto footprint = std::make_unique<geometry_msgs::msg::PolygonStamped>();
585 footprint->header = pose.header;
588 RCLCPP_DEBUG(get_logger(),
"Publishing footprint");
589 footprint_pub_->publish(std::move(footprint));
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();
605 for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
606 plugin != plugins->end();
609 (*plugin)->activate();
611 for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
612 filter != filters->end();
615 (*filter)->activate();
619 stop_updates_ =
false;
622 rclcpp::Rate r(20.0);
623 while (rclcpp::ok() && !initialized_) {
624 RCLCPP_DEBUG(get_logger(),
"Sleeping, waiting for initialized_");
632 stop_updates_ =
true;
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();
640 for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
641 plugin != plugins->end(); ++plugin)
643 (*plugin)->deactivate();
645 for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
646 filter != filters->end(); ++filter)
648 (*filter)->deactivate();
651 initialized_ =
false;
658 stop_updates_ =
true;
659 initialized_ =
false;
665 stop_updates_ =
false;
668 rclcpp::Rate r(100.0);
669 while (!initialized_) {
677 Costmap2D * top = layered_costmap_->getCostmap();
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)
688 for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
689 filter != filters->end(); ++filter)
698 return nav2_util::getCurrentPose(
699 global_pose, *tf_buffer_,
705 const geometry_msgs::msg::PoseStamped & input_pose,
706 geometry_msgs::msg::PoseStamped & transformed_pose)
709 transformed_pose = input_pose;
712 return nav2_util::transformPoseInTargetFrame(
713 input_pose, transformed_pose, *tf_buffer_,
718 rcl_interfaces::msg::SetParametersResult
721 auto result = rcl_interfaces::msg::SetParametersResult();
722 bool resize_map =
false;
723 std::lock_guard<std::mutex> lock_reinit(_dynamic_parameter_mutex);
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) {
733 if (param_type == ParameterType::PARAMETER_DOUBLE) {
734 if (param_name ==
"robot_radius") {
735 robot_radius_ = parameter.as_double();
740 }
else if (param_name ==
"footprint_padding") {
741 footprint_padding_ = parameter.as_double();
742 padded_footprint_ = unpadded_footprint_;
744 layered_costmap_->setFootprint(padded_footprint_);
745 }
else if (param_name ==
"transform_tolerance") {
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_);
752 publish_cycle_ = rclcpp::Duration(-1s);
754 }
else if (param_name ==
"resolution") {
756 resolution_ = parameter.as_double();
757 }
else if (param_name ==
"origin_x") {
759 origin_x_ = parameter.as_double();
760 }
else if (param_name ==
"origin_y") {
762 origin_y_ = parameter.as_double();
764 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
765 if (param_name ==
"width") {
766 if (parameter.as_int() > 0) {
768 map_width_meters_ = parameter.as_int();
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;
776 }
else if (param_name ==
"height") {
777 if (parameter.as_int() > 0) {
779 map_height_meters_ = parameter.as_int();
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;
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;
795 }
else if (param_name ==
"robot_base_frame") {
798 std::string tf_error;
799 RCLCPP_INFO(get_logger(),
"Checking transform");
800 if (!tf_buffer_->canTransform(
802 tf2::durationFromSec(1.0), &tf_error))
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());
809 get_logger(),
"Rejecting robot_base_frame change to %s , leaving it to its original"
811 result.successful =
false;
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_);
826 result.successful =
true;
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)
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;
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);
850 double yaw = tf2::getYaw(pose_transformed.pose.orientation);
852 if (request->use_footprint) {
853 Footprint footprint = layered_costmap_->getFootprint();
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);
860 response->costs.push_back(
862 pose_transformed.pose.position.x,
863 pose_transformed.pose.position.y, yaw, footprint));
866 get_logger(),
"Received request to get cost at point (%f, %f)",
867 pose_transformed.pose.position.x,
868 pose_transformed.pose.position.y);
871 pose_transformed.pose.position.x,
872 pose_transformed.pose.position.y, mx, my);
875 response->success =
false;
876 response->costs.push_back(LETHAL_OBSTACLE);
880 response->costs.push_back(
static_cast<float>(costmap->
getCost(mx, my)));
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
~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 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.
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)
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.