Nav2 Navigation Stack - kilted  kilted
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.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"
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 
99  void init();
100 
104  ~Costmap2DROS();
105 
109  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
110 
114  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
115 
119  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
120 
124  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
125 
129  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
130 
136  void on_rcl_preshutdown() override
137  {
139  // Transitioning handled by parent node
140  return;
141  }
142 
143  // Else, if this is an independent node, this node needs to handle itself.
144  RCLCPP_INFO(
145  get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)",
146  this->get_name());
147 
148  runCleanups();
149 
150  destroyBond();
151  }
152 
158  void start();
159 
163  void stop();
164 
168  void pause();
169 
173  void resume();
174 
178  void updateMap();
179 
183  void resetLayers();
184 
186  bool isCurrent()
187  {
188  return layered_costmap_->isCurrent();
189  }
190 
196  bool getRobotPose(geometry_msgs::msg::PoseStamped & global_pose);
197 
205  const geometry_msgs::msg::PoseStamped & input_pose,
206  geometry_msgs::msg::PoseStamped & transformed_pose);
207 
209  std::string getName() const
210  {
211  return name_;
212  }
213 
215  double getTransformTolerance() const
216  {
217  return transform_tolerance_;
218  }
219 
226  {
227  return layered_costmap_->getCostmap();
228  }
229 
234  std::string getGlobalFrameID()
235  {
236  return global_frame_;
237  }
238 
243  std::string getBaseFrameID()
244  {
245  return robot_base_frame_;
246  }
247 
252  {
253  return layered_costmap_.get();
254  }
255 
257  geometry_msgs::msg::Polygon getRobotFootprintPolygon()
258  {
259  return nav2_costmap_2d::toPolygon(padded_footprint_);
260  }
261 
270  std::vector<geometry_msgs::msg::Point> getRobotFootprint()
271  {
272  return padded_footprint_;
273  }
274 
282  std::vector<geometry_msgs::msg::Point> getUnpaddedRobotFootprint()
283  {
284  return unpadded_footprint_;
285  }
286 
291  void getOrientedFootprint(std::vector<geometry_msgs::msg::Point> & oriented_footprint);
292 
303  void setRobotFootprint(const std::vector<geometry_msgs::msg::Point> & points);
304 
315  void setRobotFootprintPolygon(const geometry_msgs::msg::Polygon::SharedPtr footprint);
316 
317  std::shared_ptr<tf2_ros::Buffer> getTfBuffer() {return tf_buffer_;}
318 
325  bool getUseRadius() {return use_radius_;}
326 
333  double getRobotRadius() {return robot_radius_;}
334 
339  void getCostsCallback(
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);
343 
344 protected:
345  // Publishers and subscribers
346  rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PolygonStamped>::SharedPtr
347  footprint_pub_;
348  std::unique_ptr<Costmap2DPublisher> costmap_publisher_;
349 
350  std::vector<std::unique_ptr<Costmap2DPublisher>> layer_publishers_;
351 
352  rclcpp::Subscription<geometry_msgs::msg::Polygon>::SharedPtr footprint_sub_;
353  rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_sub_;
354 
355  // Dedicated callback group and executor for tf timer_interface and message filter
356  rclcpp::CallbackGroup::SharedPtr callback_group_;
357  rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
358  std::unique_ptr<nav2_util::NodeThread> executor_thread_;
359 
360  // Transform listener
361  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
362  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
363 
364  std::unique_ptr<LayeredCostmap> layered_costmap_{nullptr};
365  std::string name_;
366 
370  void mapUpdateLoop(double frequency);
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;
376  std::unique_ptr<std::thread> map_update_thread_;
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"};
380 
384  void getParameters();
385  bool always_send_full_costmap_{false};
386  std::string footprint_;
387  float footprint_padding_{0};
388  std::string global_frame_;
389  int map_height_meters_{0};
390  double map_publish_frequency_{0};
391  double map_update_frequency_{0};
392  int map_width_meters_{0};
393  double origin_x_{0};
394  double origin_y_{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};
402  std::string robot_base_frame_;
403  double robot_radius_;
404  bool rolling_window_{false};
405  bool track_unknown_space_{false};
408  double map_vis_z_{0};
409 
411 
412  // Derived parameters
413  bool use_radius_{false};
414  std::vector<geometry_msgs::msg::Point> unpadded_footprint_;
415  std::vector<geometry_msgs::msg::Point> padded_footprint_;
416 
417  // Services
418  nav2_util::ServiceServer<nav2_msgs::srv::GetCosts,
419  std::shared_ptr<nav2_util::LifecycleNode>>::SharedPtr get_cost_service_;
420  std::unique_ptr<ClearCostmapService> clear_costmap_service_;
421 
422  // Dynamic parameters handler
423  OnSetParametersCallbackHandle::SharedPtr dyn_params_handler;
424 
429  rcl_interfaces::msg::SetParametersResult
430  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
431 };
432 
433 } // namespace nav2_costmap_2d
434 
435 #endif // NAV2_COSTMAP_2D__COSTMAP_2D_ROS_HPP_
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.
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".
Definition: costmap_2d.hpp:69
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.
Definition: footprint.cpp:92