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_ros_common/node_utils.hpp"
50 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
51 #include "tf2_ros/create_timer_ros.hpp"
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::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 const rclcpp::NodeOptions & parent_options)
80 std::vector<std::string> new_arguments = parent_options.arguments();
81 nav2::replaceOrAddArgument(new_arguments,
"-r",
"__ns",
82 "__ns:=" + nav2::add_namespaces(parent_namespace, name));
83 nav2::replaceOrAddArgument(new_arguments,
"-r",
"__node", name +
":" +
"__node:=" + name);
84 nav2::replaceOrAddArgument(new_arguments,
"-p",
"use_sim_time",
85 "use_sim_time:=" + std::string(use_sim_time ?
"true" :
"false"));
86 return rclcpp::NodeOptions().arguments(new_arguments);
90 const std::string & name,
91 const std::string & parent_namespace,
92 const bool & use_sim_time,
93 const rclcpp::NodeOptions & options)
94 : nav2::LifecycleNode(name,
"",
98 default_plugins_{
"static_layer",
"obstacle_layer",
"inflation_layer"},
100 "nav2_costmap_2d::StaticLayer",
101 "nav2_costmap_2d::ObstacleLayer",
102 "nav2_costmap_2d::InflationLayer"}
109 RCLCPP_INFO(get_logger(),
"Creating Costmap");
111 declare_parameter(
"always_send_full_costmap", rclcpp::ParameterValue(
false));
112 declare_parameter(
"map_vis_z", rclcpp::ParameterValue(0.0));
113 declare_parameter(
"footprint_padding", rclcpp::ParameterValue(0.01f));
114 declare_parameter(
"footprint", rclcpp::ParameterValue(std::string(
"[]")));
115 declare_parameter(
"global_frame", rclcpp::ParameterValue(std::string(
"map")));
116 declare_parameter(
"height", rclcpp::ParameterValue(5));
117 declare_parameter(
"width", rclcpp::ParameterValue(5));
118 declare_parameter(
"lethal_cost_threshold", rclcpp::ParameterValue(100));
119 declare_parameter(
"observation_sources", rclcpp::ParameterValue(std::string(
"")));
120 declare_parameter(
"origin_x", rclcpp::ParameterValue(0.0));
121 declare_parameter(
"origin_y", rclcpp::ParameterValue(0.0));
122 declare_parameter(
"plugins", rclcpp::ParameterValue(default_plugins_));
123 declare_parameter(
"filters", rclcpp::ParameterValue(std::vector<std::string>()));
124 declare_parameter(
"publish_frequency", rclcpp::ParameterValue(1.0));
125 declare_parameter(
"resolution", rclcpp::ParameterValue(0.1));
126 declare_parameter(
"robot_base_frame", rclcpp::ParameterValue(std::string(
"base_link")));
127 declare_parameter(
"robot_radius", rclcpp::ParameterValue(0.1));
128 declare_parameter(
"rolling_window", rclcpp::ParameterValue(
false));
129 declare_parameter(
"track_unknown_space", rclcpp::ParameterValue(
false));
130 declare_parameter(
"transform_tolerance", rclcpp::ParameterValue(0.3));
131 declare_parameter(
"initial_transform_timeout", rclcpp::ParameterValue(60.0));
132 declare_parameter(
"trinary_costmap", rclcpp::ParameterValue(
true));
133 declare_parameter(
"unknown_cost_value", rclcpp::ParameterValue(
static_cast<unsigned char>(0xff)));
134 declare_parameter(
"update_frequency", rclcpp::ParameterValue(5.0));
135 declare_parameter(
"use_maximum", rclcpp::ParameterValue(
false));
136 declare_parameter(
"subscribe_to_stamped_footprint", rclcpp::ParameterValue(
false));
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::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);
189 plugin->initialize(layered_costmap_.get(), plugin_names_[i], tf_buffer_.get(),
191 }
catch (
const std::exception & e) {
192 RCLCPP_ERROR(get_logger(),
"Failed to initialize costmap plugin %s! %s.",
193 plugin_names_[i].c_str(), e.what());
194 return nav2::CallbackReturn::FAILURE;
199 RCLCPP_INFO(get_logger(),
"Initialized plugin \"%s\"", plugin_names_[i].c_str());
202 for (
unsigned int i = 0; i < filter_names_.size(); ++i) {
203 RCLCPP_INFO(get_logger(),
"Using costmap filter \"%s\"", filter_names_[i].c_str());
205 std::shared_ptr<Layer> filter = plugin_loader_.createSharedInstance(filter_types_[i]);
208 std::unique_lock<Costmap2D::mutex_t> lock(*(layered_costmap_->getCostmap()->getMutex()));
210 layered_costmap_->addFilter(filter);
213 layered_costmap_.get(), filter_names_[i], tf_buffer_.get(),
218 RCLCPP_INFO(get_logger(),
"Initialized costmap filter \"%s\"", filter_names_[i].c_str());
223 footprint_stamped_sub_ = create_subscription<geometry_msgs::msg::PolygonStamped>(
224 "footprint", [
this](
const geometry_msgs::msg::PolygonStamped::SharedPtr footprint)
227 footprint_sub_ = create_subscription<geometry_msgs::msg::Polygon>(
228 "footprint", [
this](
const geometry_msgs::msg::Polygon::SharedPtr footprint)
232 footprint_pub_ = create_publisher<geometry_msgs::msg::PolygonStamped>(
233 "published_footprint");
235 costmap_publisher_ = std::make_unique<Costmap2DPublisher>(
238 "costmap", always_send_full_costmap_,
map_vis_z_);
240 auto layers = layered_costmap_->getPlugins();
242 for (
auto & layer : *layers) {
243 auto costmap_layer = std::dynamic_pointer_cast<CostmapLayer>(layer);
244 if (costmap_layer !=
nullptr) {
245 layer_publishers_.emplace_back(
246 std::make_unique<Costmap2DPublisher>(
249 layer->getName(), always_send_full_costmap_,
map_vis_z_)
258 std::vector<geometry_msgs::msg::Point> new_footprint;
264 get_cost_service_ = create_service<nav2_msgs::srv::GetCosts>(
265 std::string(
"get_cost_") + get_name(),
267 std::placeholders::_3));
270 clear_costmap_service_ = std::make_unique<ClearCostmapService>(
shared_from_this(), *
this);
272 executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
273 executor_->add_callback_group(callback_group_, get_node_base_interface());
274 executor_thread_ = std::make_unique<nav2::NodeThread>(executor_);
275 return nav2::CallbackReturn::SUCCESS;
281 RCLCPP_INFO(get_logger(),
"Activating");
286 std::string tf_error;
288 RCLCPP_INFO(get_logger(),
"Checking transform");
290 const auto initial_transform_timeout = rclcpp::Duration::from_seconds(
292 const auto initial_transform_timeout_point = now() + initial_transform_timeout;
293 while (rclcpp::ok() &&
294 !tf_buffer_->canTransform(
298 get_logger(),
"Timed out waiting for transform from %s to %s"
299 " to become available, tf error: %s",
303 if (now() > initial_transform_timeout_point) {
306 "Failed to activate %s because "
307 "transform from %s to %s did not become available before timeout",
310 return nav2::CallbackReturn::FAILURE;
320 footprint_pub_->on_activate();
321 costmap_publisher_->on_activate();
323 for (
auto & layer_pub : layer_publishers_) {
324 layer_pub->on_activate();
329 stop_updates_ =
false;
330 map_update_thread_shutdown_ =
false;
337 dyn_params_handler = this->add_on_set_parameters_callback(
340 return nav2::CallbackReturn::SUCCESS;
346 RCLCPP_INFO(get_logger(),
"Deactivating");
348 remove_on_set_parameters_callback(dyn_params_handler.get());
349 dyn_params_handler.reset();
354 map_update_thread_shutdown_ =
true;
360 footprint_pub_->on_deactivate();
361 costmap_publisher_->on_deactivate();
363 for (
auto & layer_pub : layer_publishers_) {
364 layer_pub->on_deactivate();
367 return nav2::CallbackReturn::SUCCESS;
373 RCLCPP_INFO(get_logger(),
"Cleaning up");
374 executor_thread_.reset();
375 get_cost_service_.reset();
376 costmap_publisher_.reset();
377 clear_costmap_service_.reset();
379 layer_publishers_.clear();
381 layered_costmap_.reset();
383 tf_listener_.reset();
386 footprint_sub_.reset();
387 footprint_pub_.reset();
389 return nav2::CallbackReturn::SUCCESS;
395 RCLCPP_INFO(get_logger(),
"Shutting down");
396 return nav2::CallbackReturn::SUCCESS;
402 RCLCPP_DEBUG(get_logger(),
" getParameters");
405 get_parameter(
"always_send_full_costmap", always_send_full_costmap_);
407 get_parameter(
"footprint", footprint_);
408 get_parameter(
"footprint_padding", footprint_padding_);
410 get_parameter(
"height", map_height_meters_);
411 get_parameter(
"origin_x", origin_x_);
412 get_parameter(
"origin_y", origin_y_);
413 get_parameter(
"publish_frequency", map_publish_frequency_);
414 get_parameter(
"resolution", resolution_);
416 get_parameter(
"robot_radius", robot_radius_);
418 get_parameter(
"track_unknown_space", track_unknown_space_);
421 get_parameter(
"update_frequency", map_update_frequency_);
422 get_parameter(
"width", map_width_meters_);
423 get_parameter(
"plugins", plugin_names_);
424 get_parameter(
"filters", filter_names_);
429 if (plugin_names_ == default_plugins_) {
430 for (
size_t i = 0; i < default_plugins_.size(); ++i) {
431 nav2::declare_parameter_if_not_declared(
432 node, default_plugins_[i] +
".plugin", rclcpp::ParameterValue(default_types_[i]));
435 plugin_types_.resize(plugin_names_.size());
436 filter_types_.resize(filter_names_.size());
439 for (
size_t i = 0; i < plugin_names_.size(); ++i) {
440 plugin_types_[i] = nav2::get_plugin_type_param(node, plugin_names_[i]);
442 for (
size_t i = 0; i < filter_names_.size(); ++i) {
443 filter_types_[i] = nav2::get_plugin_type_param(node, filter_names_[i]);
447 if (map_publish_frequency_ > 0) {
448 publish_cycle_ = rclcpp::Duration::from_seconds(1 / map_publish_frequency_);
450 publish_cycle_ = rclcpp::Duration(-1s);
456 if (footprint_ !=
"" && footprint_ !=
"[]") {
458 std::vector<geometry_msgs::msg::Point> new_footprint;
465 get_logger(),
"The footprint parameter is invalid: \"%s\", using radius (%lf) instead",
466 footprint_.c_str(), robot_radius_);
471 if (map_width_meters_ <= 0) {
473 get_logger(),
"You try to set width of map to be negative or zero,"
474 " this isn't allowed, please give a positive value.");
476 if (map_height_meters_ <= 0) {
478 get_logger(),
"You try to set height of map to be negative or zero,"
479 " this isn't allowed, please give a positive value.");
486 unpadded_footprint_ = points;
487 padded_footprint_ = points;
489 layered_costmap_->setFootprint(padded_footprint_);
494 const geometry_msgs::msg::Polygon & footprint)
502 geometry_msgs::msg::PoseStamped global_pose;
507 double yaw = tf2::getYaw(global_pose.pose.orientation);
509 global_pose.pose.position.x, global_pose.pose.position.y, yaw,
510 padded_footprint_, oriented_footprint);
516 RCLCPP_DEBUG(get_logger(),
"mapUpdateLoop frequency: %lf", frequency);
519 if (frequency == 0.0) {
523 RCLCPP_DEBUG(get_logger(),
"Entering loop");
525 rclcpp::WallRate r(frequency);
527 while (rclcpp::ok() && !map_update_thread_shutdown_) {
533 std::scoped_lock<std::mutex> lock(_dynamic_parameter_mutex);
541 if (publish_cycle_ > rclcpp::Duration(0s) && layered_costmap_->isInitialized()) {
542 unsigned int x0, y0, xn, yn;
543 layered_costmap_->getBounds(&x0, &xn, &y0, &yn);
544 costmap_publisher_->updateBounds(x0, xn, y0, yn);
546 for (
auto & layer_pub : layer_publishers_) {
547 layer_pub->updateBounds(x0, xn, y0, yn);
550 auto current_time = now();
551 if ((last_publish_ + publish_cycle_ < current_time) ||
555 RCLCPP_DEBUG(get_logger(),
"Publish costmap at %s", name_.c_str());
556 costmap_publisher_->publishCostmap();
558 for (
auto & layer_pub : layer_publishers_) {
559 layer_pub->publishCostmap();
562 last_publish_ = current_time;
572 if (r.period() > tf2::durationFromSec(1 / frequency)) {
575 "Costmap2DROS: Map update loop missed its desired rate of %.4fHz... "
576 "the loop actually took %.4f seconds", frequency, r.period());
585 RCLCPP_DEBUG(get_logger(),
"Updating map...");
587 if (!stop_updates_) {
589 geometry_msgs::msg::PoseStamped pose;
591 const double & x = pose.pose.position.x;
592 const double & y = pose.pose.position.y;
593 const double yaw = tf2::getYaw(pose.pose.orientation);
594 layered_costmap_->updateMap(x, y, yaw);
596 auto footprint = std::make_unique<geometry_msgs::msg::PolygonStamped>();
597 footprint->header = pose.header;
600 RCLCPP_DEBUG(get_logger(),
"Publishing footprint");
601 footprint_pub_->publish(std::move(footprint));
610 RCLCPP_INFO(get_logger(),
"start");
611 std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
612 std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
617 for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
618 plugin != plugins->end();
621 (*plugin)->activate();
623 for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
624 filter != filters->end();
627 (*filter)->activate();
631 stop_updates_ =
false;
634 rclcpp::Rate r(20.0);
635 while (rclcpp::ok() && !initialized_) {
636 RCLCPP_DEBUG(get_logger(),
"Sleeping, waiting for initialized_");
644 stop_updates_ =
true;
647 if (layered_costmap_) {
648 std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
649 std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
652 for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
653 plugin != plugins->end(); ++plugin)
655 (*plugin)->deactivate();
657 for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
658 filter != filters->end(); ++filter)
660 (*filter)->deactivate();
663 initialized_ =
false;
670 stop_updates_ =
true;
671 initialized_ =
false;
677 stop_updates_ =
false;
680 rclcpp::Rate r(100.0);
681 while (!initialized_) {
689 Costmap2D * top = layered_costmap_->getCostmap();
693 std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
694 std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
695 for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
696 plugin != plugins->end(); ++plugin)
700 for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
701 filter != filters->end(); ++filter)
710 return nav2_util::getCurrentPose(
711 global_pose, *tf_buffer_,
717 const geometry_msgs::msg::PoseStamped & input_pose,
718 geometry_msgs::msg::PoseStamped & transformed_pose)
721 transformed_pose = input_pose;
724 return nav2_util::transformPoseInTargetFrame(
725 input_pose, transformed_pose, *tf_buffer_,
730 rcl_interfaces::msg::SetParametersResult
733 auto result = rcl_interfaces::msg::SetParametersResult();
734 bool resize_map =
false;
735 std::lock_guard<std::mutex> lock_reinit(_dynamic_parameter_mutex);
737 for (
auto parameter : parameters) {
738 const auto & param_type = parameter.get_type();
739 const auto & param_name = parameter.get_name();
740 if (param_name.find(
'.') != std::string::npos) {
745 if (param_type == ParameterType::PARAMETER_DOUBLE) {
746 if (param_name ==
"robot_radius") {
747 robot_radius_ = parameter.as_double();
752 }
else if (param_name ==
"footprint_padding") {
753 footprint_padding_ = parameter.as_double();
754 padded_footprint_ = unpadded_footprint_;
756 layered_costmap_->setFootprint(padded_footprint_);
757 }
else if (param_name ==
"transform_tolerance") {
759 }
else if (param_name ==
"publish_frequency") {
760 map_publish_frequency_ = parameter.as_double();
761 if (map_publish_frequency_ > 0) {
762 publish_cycle_ = rclcpp::Duration::from_seconds(1 / map_publish_frequency_);
764 publish_cycle_ = rclcpp::Duration(-1s);
766 }
else if (param_name ==
"resolution") {
768 resolution_ = parameter.as_double();
769 }
else if (param_name ==
"origin_x") {
771 origin_x_ = parameter.as_double();
772 }
else if (param_name ==
"origin_y") {
774 origin_y_ = parameter.as_double();
776 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
777 if (param_name ==
"width") {
778 if (parameter.as_int() > 0) {
780 map_width_meters_ = parameter.as_int();
783 get_logger(),
"You try to set width of map to be negative or zero,"
784 " this isn't allowed, please give a positive value.");
785 result.successful =
false;
788 }
else if (param_name ==
"height") {
789 if (parameter.as_int() > 0) {
791 map_height_meters_ = parameter.as_int();
794 get_logger(),
"You try to set height of map to be negative or zero,"
795 " this isn't allowed, please give a positive value.");
796 result.successful =
false;
800 }
else if (param_type == ParameterType::PARAMETER_STRING) {
801 if (param_name ==
"footprint") {
802 footprint_ = parameter.as_string();
803 std::vector<geometry_msgs::msg::Point> new_footprint;
807 }
else if (param_name ==
"robot_base_frame") {
810 std::string tf_error;
811 RCLCPP_INFO(get_logger(),
"Checking transform");
812 if (!tf_buffer_->canTransform(
814 tf2::durationFromSec(1.0), &tf_error))
817 get_logger(),
"Timed out waiting for transform from %s to %s"
818 " to become available, tf error: %s",
819 parameter.as_string().c_str(),
global_frame_.c_str(), tf_error.c_str());
821 get_logger(),
"Rejecting robot_base_frame change to %s , leaving it to its original"
823 result.successful =
false;
831 if (resize_map && !layered_costmap_->isSizeLocked()) {
832 layered_costmap_->resizeMap(
833 (
unsigned int)(map_width_meters_ / resolution_),
834 (
unsigned int)(map_height_meters_ / resolution_), resolution_, origin_x_, origin_y_);
838 result.successful =
true;
843 const std::shared_ptr<rmw_request_id_t>,
844 const std::shared_ptr<nav2_msgs::srv::GetCosts::Request> request,
845 const std::shared_ptr<nav2_msgs::srv::GetCosts::Response> response)
849 Costmap2D * costmap = layered_costmap_->getCostmap();
850 std::unique_lock<Costmap2D::mutex_t> lock(*(costmap->getMutex()));
851 response->success =
true;
852 for (
const auto & pose : request->poses) {
853 geometry_msgs::msg::PoseStamped pose_transformed;
856 get_logger(),
"Failed to transform, cannot get cost for pose (%.2f, %.2f)",
857 pose.pose.position.x, pose.pose.position.y);
858 response->success =
false;
859 response->costs.push_back(NO_INFORMATION);
862 double yaw = tf2::getYaw(pose_transformed.pose.orientation);
864 if (request->use_footprint) {
865 Footprint footprint = layered_costmap_->getFootprint();
869 get_logger(),
"Received request to get cost at footprint pose (%.2f, %.2f, %.2f)",
870 pose_transformed.pose.position.x, pose_transformed.pose.position.y, yaw);
872 response->costs.push_back(
874 pose_transformed.pose.position.x,
875 pose_transformed.pose.position.y, yaw, footprint));
878 get_logger(),
"Received request to get cost at point (%f, %f)",
879 pose_transformed.pose.position.x,
880 pose_transformed.pose.position.y);
883 pose_transformed.pose.position.x,
884 pose_transformed.pose.position.y, mx, my);
887 response->success =
false;
888 response->costs.push_back(LETHAL_OBSTACLE);
892 response->costs.push_back(
static_cast<float>(costmap->
getCost(mx, my)));
nav2::LifecycleNode::SharedPtr shared_from_this()
Get a shared pointer of this.
Costmap2DROS(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for the wrapper.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Cleanup node.
void mapUpdateLoop(double frequency)
Function on timer for costmap update.
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.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure node.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate node.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate 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 initial_transform_timeout_
The timeout before activation of the node errors.
void updateMap()
Update the map with the layered costmap / plugins.
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.
bool subscribe_to_stamped_footprint_
If true, the footprint subscriber expects a PolygonStamped msg.
void setRobotFootprintPolygon(const geometry_msgs::msg::Polygon &footprint)
Set the footprint of the robot to be the given polygon, padded by footprint_padding.
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
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
shutdown 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.
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)
rclcpp::NodeOptions getChildNodeOptions(const std::string &name, const std::string &parent_namespace, const bool &use_sim_time, const rclcpp::NodeOptions &parent_options)
Given the node options of a parent node, expands of replaces the fields for the node name,...
std::vector< geometry_msgs::msg::Point > makeFootprintFromRadius(double radius)
Create a circular footprint from a given radius.
std::vector< geometry_msgs::msg::Point > toPointVector(const geometry_msgs::msg::Polygon &polygon)
Convert Polygon msg to vector of Points.