Nav2 Navigation Stack - humble  humble
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/clear_costmap_service.hpp"
51 #include "nav2_costmap_2d/layered_costmap.hpp"
52 #include "nav2_costmap_2d/layer.hpp"
53 #include "nav2_util/lifecycle_node.hpp"
54 #include "pluginlib/class_loader.hpp"
55 #include "tf2/convert.h"
56 #include "tf2/LinearMath/Transform.h"
57 #include "tf2_ros/buffer.h"
58 #include "tf2_ros/transform_listener.h"
59 #include "tf2/time.h"
60 #include "tf2/transform_datatypes.h"
61 
62 #pragma GCC diagnostic push
63 #pragma GCC diagnostic ignored "-Wpedantic"
64 #include "tf2/utils.h"
65 #pragma GCC diagnostic pop
66 
67 namespace nav2_costmap_2d
68 {
69 
74 {
75 public:
80  Costmap2DROS(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
81 
87  explicit Costmap2DROS(const std::string & name);
88 
95  explicit Costmap2DROS(
96  const std::string & name,
97  const std::string & parent_namespace,
98  const std::string & local_namespace);
99 
103  ~Costmap2DROS();
104 
108  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
109 
113  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
114 
118  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
119 
123  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
124 
128  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
129 
135  void on_rcl_preshutdown() override
136  {
138  // Transitioning handled by parent node
139  return;
140  }
141 
142  // Else, if this is an independent node, this node needs to handle itself.
143  RCLCPP_INFO(
144  get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)",
145  this->get_name());
146 
147  runCleanups();
148 
149  destroyBond();
150  }
151 
157  void start();
158 
162  void stop();
163 
167  void pause();
168 
172  void resume();
173 
177  void updateMap();
178 
182  void resetLayers();
183 
185  bool isCurrent()
186  {
187  return layered_costmap_->isCurrent();
188  }
189 
195  bool getRobotPose(geometry_msgs::msg::PoseStamped & global_pose);
196 
204  const geometry_msgs::msg::PoseStamped & input_pose,
205  geometry_msgs::msg::PoseStamped & transformed_pose);
206 
208  std::string getName() const
209  {
210  return name_;
211  }
212 
214  double getTransformTolerance() const
215  {
216  return transform_tolerance_;
217  }
218 
225  {
226  return layered_costmap_->getCostmap();
227  }
228 
233  std::string getGlobalFrameID()
234  {
235  return global_frame_;
236  }
237 
242  std::string getBaseFrameID()
243  {
244  return robot_base_frame_;
245  }
246 
251  {
252  return layered_costmap_.get();
253  }
254 
256  geometry_msgs::msg::Polygon getRobotFootprintPolygon()
257  {
258  return nav2_costmap_2d::toPolygon(padded_footprint_);
259  }
260 
269  std::vector<geometry_msgs::msg::Point> getRobotFootprint()
270  {
271  return padded_footprint_;
272  }
273 
281  std::vector<geometry_msgs::msg::Point> getUnpaddedRobotFootprint()
282  {
283  return unpadded_footprint_;
284  }
285 
290  void getOrientedFootprint(std::vector<geometry_msgs::msg::Point> & oriented_footprint);
291 
302  void setRobotFootprint(const std::vector<geometry_msgs::msg::Point> & points);
303 
314  void setRobotFootprintPolygon(const geometry_msgs::msg::Polygon::SharedPtr footprint);
315 
316  std::shared_ptr<tf2_ros::Buffer> getTfBuffer() {return tf_buffer_;}
317 
324  bool getUseRadius() {return use_radius_;}
325 
332  double getRobotRadius() {return robot_radius_;}
333 
334 protected:
335  // Publishers and subscribers
336  rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PolygonStamped>::SharedPtr
337  footprint_pub_;
338  std::unique_ptr<Costmap2DPublisher> costmap_publisher_{nullptr};
339 
340  rclcpp::Subscription<geometry_msgs::msg::Polygon>::SharedPtr footprint_sub_;
341  rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_sub_;
342 
343  // Dedicated callback group and executor for tf timer_interface and message fillter
344  rclcpp::CallbackGroup::SharedPtr callback_group_;
345  rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
346  std::unique_ptr<nav2_util::NodeThread> executor_thread_;
347 
348  // Transform listener
349  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
350  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
351 
352  std::unique_ptr<LayeredCostmap> layered_costmap_{nullptr};
353  std::string name_;
354  std::string parent_namespace_;
355 
359  void mapUpdateLoop(double frequency);
360  bool map_update_thread_shutdown_{false};
361  std::atomic<bool> stop_updates_{false};
362  std::atomic<bool> initialized_{false};
363  std::atomic<bool> stopped_{true};
364  std::mutex _dynamic_parameter_mutex;
365  std::unique_ptr<std::thread> map_update_thread_;
366  rclcpp::Time last_publish_{0, 0, RCL_ROS_TIME};
367  rclcpp::Duration publish_cycle_{1, 0};
368  pluginlib::ClassLoader<Layer> plugin_loader_{"nav2_costmap_2d", "nav2_costmap_2d::Layer"};
369 
373  void getParameters();
374  bool always_send_full_costmap_{false};
375  std::string footprint_;
376  float footprint_padding_{0};
377  std::string global_frame_;
378  int map_height_meters_{0};
379  double map_publish_frequency_{0};
380  double map_update_frequency_{0};
381  int map_width_meters_{0};
382  double origin_x_{0};
383  double origin_y_{0};
384  std::vector<std::string> default_plugins_;
385  std::vector<std::string> default_types_;
386  std::vector<std::string> plugin_names_;
387  std::vector<std::string> plugin_types_;
388  std::vector<std::string> filter_names_;
389  std::vector<std::string> filter_types_;
390  double resolution_{0};
391  std::string robot_base_frame_;
392  double robot_radius_;
393  bool rolling_window_{false};
394  bool track_unknown_space_{false};
396 
398 
399  // Derived parameters
400  bool use_radius_{false};
401  std::vector<geometry_msgs::msg::Point> unpadded_footprint_;
402  std::vector<geometry_msgs::msg::Point> padded_footprint_;
403 
404  std::unique_ptr<ClearCostmapService> clear_costmap_service_;
405 
406  // Dynamic parameters handler
407  OnSetParametersCallbackHandle::SharedPtr dyn_params_handler;
408 
413  rcl_interfaces::msg::SetParametersResult
414  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
415 };
416 
417 } // namespace nav2_costmap_2d
418 
419 #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 paramter 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.
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.
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.
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:68
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.
geometry_msgs::msg::Polygon toPolygon(std::vector< geometry_msgs::msg::Point > pts)
Convert vector of Points to Polygon msg.
Definition: footprint.cpp:91