38 #ifndef NAV2_COSTMAP_2D__COSTMAP_2D_ROS_HPP_
39 #define NAV2_COSTMAP_2D__COSTMAP_2D_ROS_HPP_
46 #include "geometry_msgs/msg/polygon.h"
47 #include "geometry_msgs/msg/polygon_stamped.h"
48 #include "nav2_costmap_2d/costmap_2d_publisher.hpp"
49 #include "nav2_costmap_2d/footprint.hpp"
50 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
51 #include "nav2_costmap_2d/clear_costmap_service.hpp"
52 #include "nav2_costmap_2d/layered_costmap.hpp"
53 #include "nav2_costmap_2d/layer.hpp"
54 #include "nav2_util/lifecycle_node.hpp"
55 #include "nav2_msgs/srv/get_costs.hpp"
56 #include "pluginlib/class_loader.hpp"
57 #include "tf2/convert.hpp"
58 #include "tf2/LinearMath/Transform.hpp"
59 #include "tf2_ros/buffer.h"
60 #include "tf2_ros/transform_listener.h"
61 #include "tf2/time.hpp"
62 #include "tf2/transform_datatypes.hpp"
63 #include "nav2_util/service_server.hpp"
65 #pragma GCC diagnostic push
66 #pragma GCC diagnostic ignored "-Wpedantic"
67 #include "tf2/utils.hpp"
68 #pragma GCC diagnostic pop
83 explicit Costmap2DROS(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
92 const std::string & name,
93 const std::string & parent_namespace =
"/",
94 const bool & use_sim_time =
false);
109 nav2_util::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
114 nav2_util::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
119 nav2_util::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
124 nav2_util::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
129 nav2_util::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
145 get_logger(),
"Running Nav2 LifecycleNode rcl preshutdown (%s)",
188 return layered_costmap_->isCurrent();
196 bool getRobotPose(geometry_msgs::msg::PoseStamped & global_pose);
205 const geometry_msgs::msg::PoseStamped & input_pose,
206 geometry_msgs::msg::PoseStamped & transformed_pose);
227 return layered_costmap_->getCostmap();
253 return layered_costmap_.get();
272 return padded_footprint_;
284 return unpadded_footprint_;
317 std::shared_ptr<tf2_ros::Buffer> getTfBuffer() {
return tf_buffer_;}
340 const std::shared_ptr<rmw_request_id_t>,
341 const std::shared_ptr<nav2_msgs::srv::GetCosts::Request> request,
342 const std::shared_ptr<nav2_msgs::srv::GetCosts::Response> response);
346 rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PolygonStamped>::SharedPtr
348 std::unique_ptr<Costmap2DPublisher> costmap_publisher_;
350 std::vector<std::unique_ptr<Costmap2DPublisher>> layer_publishers_;
352 rclcpp::Subscription<geometry_msgs::msg::Polygon>::SharedPtr footprint_sub_;
353 rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_sub_;
356 rclcpp::CallbackGroup::SharedPtr callback_group_;
357 rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
358 std::unique_ptr<nav2_util::NodeThread> executor_thread_;
361 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
362 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
364 std::unique_ptr<LayeredCostmap> layered_costmap_{
nullptr};
371 bool map_update_thread_shutdown_{
false};
372 std::atomic<bool> stop_updates_{
false};
373 std::atomic<bool> initialized_{
false};
374 std::atomic<bool> stopped_{
true};
375 std::mutex _dynamic_parameter_mutex;
377 rclcpp::Time last_publish_{0, 0, RCL_ROS_TIME};
378 rclcpp::Duration publish_cycle_{1, 0};
379 pluginlib::ClassLoader<Layer> plugin_loader_{
"nav2_costmap_2d",
"nav2_costmap_2d::Layer"};
385 bool always_send_full_costmap_{
false};
386 std::string footprint_;
387 float footprint_padding_{0};
389 int map_height_meters_{0};
390 double map_publish_frequency_{0};
391 double map_update_frequency_{0};
392 int map_width_meters_{0};
395 std::vector<std::string> default_plugins_;
396 std::vector<std::string> default_types_;
397 std::vector<std::string> plugin_names_;
398 std::vector<std::string> plugin_types_;
399 std::vector<std::string> filter_names_;
400 std::vector<std::string> filter_types_;
401 double resolution_{0};
403 double robot_radius_;
405 bool track_unknown_space_{
false};
413 bool use_radius_{
false};
414 std::vector<geometry_msgs::msg::Point> unpadded_footprint_;
415 std::vector<geometry_msgs::msg::Point> padded_footprint_;
419 std::shared_ptr<nav2_util::LifecycleNode>>::SharedPtr get_cost_service_;
420 std::unique_ptr<ClearCostmapService> clear_costmap_service_;
423 OnSetParametersCallbackHandle::SharedPtr dyn_params_handler;
429 rcl_interfaces::msg::SetParametersResult
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 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.
geometry_msgs::msg::Polygon getRobotFootprintPolygon()
Returns the current padded footprint as a geometry_msgs::msg::Polygon.
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.
bool getUseRadius()
Get the costmap's use_radius_ parameter, corresponding to whether the footprint for the robot is a ci...
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.
LayeredCostmap * getLayeredCostmap()
Get the layered costmap object used in the node.
void on_rcl_preshutdown() override
as a child-LifecycleNode : Costmap2DROS may be launched by another Lifecycle Node as a composed modul...
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.
std::string getBaseFrameID()
Returns the local frame of the costmap.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure node.
std::vector< geometry_msgs::msg::Point > getRobotFootprint()
Return the current footprint of the robot as a vector of points.
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.
std::string getGlobalFrameID()
Returns the global frame of 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 isCurrent()
Same as getLayeredCostmap()->isCurrent().
double getTransformTolerance() const
Returns the delay in transform (tf) data that is tolerable in seconds.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Cleanup node.
double getRobotRadius()
Get the costmap's robot_radius_ parameter, corresponding to raidus of the robot footprint when it is ...
std::unique_ptr< std::thread > map_update_thread_
A thread for updating the map.
Costmap2D * getCostmap()
Return a pointer to the "master" costmap which receives updates from all the layers.
void init()
Common initialization for constructors.
std::vector< geometry_msgs::msg::Point > getUnpaddedRobotFootprint()
Return the current unpadded footprint of the robot as a vector of points.
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".
Instantiates different layer plugins and aggregates them into one score.
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
void destroyBond()
Destroy bond connection to lifecycle manager.
A simple wrapper on ROS2 services server.
geometry_msgs::msg::Polygon toPolygon(std::vector< geometry_msgs::msg::Point > pts)
Convert vector of Points to Polygon msg.