Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
costmap_2d_ros.hpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 #ifndef NAV2_COSTMAP_2D__COSTMAP_2D_ROS_HPP_
39 #define NAV2_COSTMAP_2D__COSTMAP_2D_ROS_HPP_
40 
41 #include <atomic>
42 #include <memory>
43 #include <string>
44 #include <vector>
45 
46 #include "geometry_msgs/msg/polygon.hpp"
47 #include "geometry_msgs/msg/polygon_stamped.hpp"
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_ros_common/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.hpp"
60 #include "tf2_ros/transform_listener.hpp"
61 #include "tf2/time.hpp"
62 #include "tf2/transform_datatypes.hpp"
63 #include "nav2_ros_common/service_server.hpp"
64 
65 #pragma GCC diagnostic push
66 #pragma GCC diagnostic ignored "-Wpedantic"
67 #include "tf2/utils.hpp"
68 #pragma GCC diagnostic pop
69 
70 namespace nav2_costmap_2d
71 {
72 
77 {
78 public:
83  explicit Costmap2DROS(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
84 
91  explicit Costmap2DROS(
92  const std::string & name,
93  const std::string & parent_namespace = "/",
94  const bool & use_sim_time = false,
95  const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
96 
100  void init();
101 
105  ~Costmap2DROS();
106 
110  nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
111 
115  nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
116 
120  nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
121 
125  nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
126 
130  nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
131 
137  void on_rcl_preshutdown() override
138  {
140  // Transitioning handled by parent node
141  return;
142  }
143 
144  // Else, if this is an independent node, this node needs to handle itself.
145  RCLCPP_INFO(
146  get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)",
147  this->get_name());
148 
149  runCleanups();
150 
151  destroyBond();
152  }
153 
159  void start();
160 
164  void stop();
165 
169  void pause();
170 
174  void resume();
175 
179  void updateMap();
180 
184  void resetLayers();
185 
187  bool isCurrent()
188  {
189  return layered_costmap_->isCurrent();
190  }
191 
197  bool getRobotPose(geometry_msgs::msg::PoseStamped & global_pose);
198 
206  const geometry_msgs::msg::PoseStamped & input_pose,
207  geometry_msgs::msg::PoseStamped & transformed_pose);
208 
210  std::string getName() const
211  {
212  return name_;
213  }
214 
216  double getTransformTolerance() const
217  {
218  return transform_tolerance_;
219  }
220 
227  {
228  return layered_costmap_->getCostmap();
229  }
230 
235  std::string getGlobalFrameID()
236  {
237  return global_frame_;
238  }
239 
244  std::string getBaseFrameID()
245  {
246  return robot_base_frame_;
247  }
248 
253  {
254  return layered_costmap_.get();
255  }
256 
258  geometry_msgs::msg::Polygon getRobotFootprintPolygon()
259  {
260  return nav2_costmap_2d::toPolygon(padded_footprint_);
261  }
262 
271  std::vector<geometry_msgs::msg::Point> getRobotFootprint()
272  {
273  return padded_footprint_;
274  }
275 
283  std::vector<geometry_msgs::msg::Point> getUnpaddedRobotFootprint()
284  {
285  return unpadded_footprint_;
286  }
287 
292  void getOrientedFootprint(std::vector<geometry_msgs::msg::Point> & oriented_footprint);
293 
304  void setRobotFootprint(const std::vector<geometry_msgs::msg::Point> & points);
305 
316  void setRobotFootprintPolygon(const geometry_msgs::msg::Polygon & footprint);
317 
318  std::shared_ptr<tf2_ros::Buffer> getTfBuffer() {return tf_buffer_;}
319 
326  bool getUseRadius() {return use_radius_;}
327 
334  double getRobotRadius() {return robot_radius_;}
335 
340  void getCostsCallback(
341  const std::shared_ptr<rmw_request_id_t>,
342  const std::shared_ptr<nav2_msgs::srv::GetCosts::Request> request,
343  const std::shared_ptr<nav2_msgs::srv::GetCosts::Response> response);
344 
345 protected:
346  // Publishers and subscribers
347  nav2::Publisher<geometry_msgs::msg::PolygonStamped>::SharedPtr
348  footprint_pub_;
349  std::unique_ptr<Costmap2DPublisher> costmap_publisher_;
350 
351  std::vector<std::unique_ptr<Costmap2DPublisher>> layer_publishers_;
352 
353  nav2::Subscription<geometry_msgs::msg::Polygon>::SharedPtr footprint_sub_;
354  nav2::Subscription<geometry_msgs::msg::PolygonStamped>::SharedPtr footprint_stamped_sub_;
355  nav2::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_sub_;
356 
357  // Dedicated callback group and executor for tf timer_interface and message filter
358  rclcpp::CallbackGroup::SharedPtr callback_group_;
359  rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
360  std::unique_ptr<nav2::NodeThread> executor_thread_;
361 
362  // Transform listener
363  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
364  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
365 
366  std::unique_ptr<LayeredCostmap> layered_costmap_{nullptr};
367  std::string name_;
368 
372  void mapUpdateLoop(double frequency);
373  bool map_update_thread_shutdown_{false};
374  std::atomic<bool> stop_updates_{false};
375  std::atomic<bool> initialized_{false};
376  std::atomic<bool> stopped_{true};
377  std::mutex _dynamic_parameter_mutex;
378  std::unique_ptr<std::thread> map_update_thread_;
379  rclcpp::Time last_publish_{0, 0, RCL_ROS_TIME};
380  rclcpp::Duration publish_cycle_{1, 0};
381  pluginlib::ClassLoader<Layer> plugin_loader_{"nav2_costmap_2d", "nav2_costmap_2d::Layer"};
382 
386  void getParameters();
387  bool always_send_full_costmap_{false};
388  std::string footprint_;
389  float footprint_padding_{0};
390  std::string global_frame_;
391  int map_height_meters_{0};
392  double map_publish_frequency_{0};
393  double map_update_frequency_{0};
394  int map_width_meters_{0};
395  double origin_x_{0};
396  double origin_y_{0};
397  std::vector<std::string> default_plugins_;
398  std::vector<std::string> default_types_;
399  std::vector<std::string> plugin_names_;
400  std::vector<std::string> plugin_types_;
401  std::vector<std::string> filter_names_;
402  std::vector<std::string> filter_types_;
403  double resolution_{0};
404  std::string robot_base_frame_;
405  double robot_radius_;
406  bool rolling_window_{false};
407  bool track_unknown_space_{false};
410  double map_vis_z_{0};
413 
415 
416  // Derived parameters
417  bool use_radius_{false};
418  std::vector<geometry_msgs::msg::Point> unpadded_footprint_;
419  std::vector<geometry_msgs::msg::Point> padded_footprint_;
420 
421  // Services
422  nav2::ServiceServer<nav2_msgs::srv::GetCosts>::SharedPtr get_cost_service_;
423  std::unique_ptr<ClearCostmapService> clear_costmap_service_;
424 
425  // Dynamic parameters handler
426  OnSetParametersCallbackHandle::SharedPtr dyn_params_handler;
427 
432  rcl_interfaces::msg::SetParametersResult
433  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
434 };
435 
436 // free functions
437 
442 rclcpp::NodeOptions getChildNodeOptions(
443  const std::string & name,
444  const std::string & parent_namespace,
445  const bool & use_sim_time,
446  const rclcpp::NodeOptions & parent_options);
447 
448 } // namespace nav2_costmap_2d
449 
450 #endif // NAV2_COSTMAP_2D__COSTMAP_2D_ROS_HPP_
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
void destroyBond()
Destroy bond connection to lifecycle manager.
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.
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.
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.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure node.
bool getUseRadius()
Get the costmap's use_radius_ parameter, corresponding to whether the footprint for the robot is a ci...
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate node.
std::string getName() const
Returns costmap name.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate node.
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 initial_transform_timeout_
The timeout before activation of the node errors.
void updateMap()
Update the map with the layered costmap / plugins.
std::string getBaseFrameID()
Returns the local frame of the costmap.
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 subscribe_to_stamped_footprint_
If true, the footprint subscriber expects a PolygonStamped msg.
bool isCurrent()
Same as getLayeredCostmap()->isCurrent().
double getTransformTolerance() const
Returns the delay in transform (tf) data that is tolerable in seconds.
double getRobotRadius()
Get the costmap's robot_radius_ parameter, corresponding to raidus of the robot footprint when it is ...
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.
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
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".
Definition: costmap_2d.hpp:69
Instantiates different layer plugins and aggregates them into one score.
geometry_msgs::msg::Polygon toPolygon(const std::vector< geometry_msgs::msg::Point > &pts)
Convert vector of Points to Polygon msg.
Definition: footprint.cpp:92
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,...