Nav2 Navigation Stack - jazzy  jazzy
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_cost.hpp"
56 #include "pluginlib/class_loader.hpp"
57 #include "tf2/convert.h"
58 #include "tf2/LinearMath/Transform.h"
59 #include "tf2_ros/buffer.h"
60 #include "tf2_ros/transform_listener.h"
61 #include "tf2/time.h"
62 #include "tf2/transform_datatypes.h"
63 
64 #pragma GCC diagnostic push
65 #pragma GCC diagnostic ignored "-Wpedantic"
66 #include "tf2/utils.h"
67 #pragma GCC diagnostic pop
68 
69 namespace nav2_costmap_2d
70 {
71 
76 {
77 public:
82  explicit Costmap2DROS(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
83 
90  explicit Costmap2DROS(const std::string & name, const bool & use_sim_time = false);
91 
99  explicit Costmap2DROS(
100  const std::string & name,
101  const std::string & parent_namespace,
102  const std::string & local_namespace,
103  const bool & use_sim_time);
104 
108  void init();
109 
113  ~Costmap2DROS();
114 
118  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
119 
123  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
124 
128  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
129 
133  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
134 
138  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
139 
145  void on_rcl_preshutdown() override
146  {
148  // Transitioning handled by parent node
149  return;
150  }
151 
152  // Else, if this is an independent node, this node needs to handle itself.
153  RCLCPP_INFO(
154  get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)",
155  this->get_name());
156 
157  runCleanups();
158 
159  destroyBond();
160  }
161 
167  void start();
168 
172  void stop();
173 
177  void pause();
178 
182  void resume();
183 
187  void updateMap();
188 
192  void resetLayers();
193 
195  bool isCurrent()
196  {
197  return layered_costmap_->isCurrent();
198  }
199 
205  bool getRobotPose(geometry_msgs::msg::PoseStamped & global_pose);
206 
214  const geometry_msgs::msg::PoseStamped & input_pose,
215  geometry_msgs::msg::PoseStamped & transformed_pose);
216 
218  std::string getName() const
219  {
220  return name_;
221  }
222 
224  double getTransformTolerance() const
225  {
226  return transform_tolerance_;
227  }
228 
235  {
236  return layered_costmap_->getCostmap();
237  }
238 
243  std::string getGlobalFrameID()
244  {
245  return global_frame_;
246  }
247 
252  std::string getBaseFrameID()
253  {
254  return robot_base_frame_;
255  }
256 
261  {
262  return layered_costmap_.get();
263  }
264 
266  geometry_msgs::msg::Polygon getRobotFootprintPolygon()
267  {
268  return nav2_costmap_2d::toPolygon(padded_footprint_);
269  }
270 
279  std::vector<geometry_msgs::msg::Point> getRobotFootprint()
280  {
281  return padded_footprint_;
282  }
283 
291  std::vector<geometry_msgs::msg::Point> getUnpaddedRobotFootprint()
292  {
293  return unpadded_footprint_;
294  }
295 
300  void getOrientedFootprint(std::vector<geometry_msgs::msg::Point> & oriented_footprint);
301 
312  void setRobotFootprint(const std::vector<geometry_msgs::msg::Point> & points);
313 
324  void setRobotFootprintPolygon(const geometry_msgs::msg::Polygon::SharedPtr footprint);
325 
326  std::shared_ptr<tf2_ros::Buffer> getTfBuffer() {return tf_buffer_;}
327 
334  bool getUseRadius() {return use_radius_;}
335 
342  double getRobotRadius() {return robot_radius_;}
343 
348  void getCostCallback(
349  const std::shared_ptr<rmw_request_id_t>,
350  const std::shared_ptr<nav2_msgs::srv::GetCost::Request> request,
351  const std::shared_ptr<nav2_msgs::srv::GetCost::Response> response);
352 
353 protected:
354  // Publishers and subscribers
355  rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PolygonStamped>::SharedPtr
356  footprint_pub_;
357  std::unique_ptr<Costmap2DPublisher> costmap_publisher_;
358 
359  std::vector<std::unique_ptr<Costmap2DPublisher>> layer_publishers_;
360 
361  rclcpp::Subscription<geometry_msgs::msg::Polygon>::SharedPtr footprint_sub_;
362  rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_sub_;
363 
364  // Dedicated callback group and executor for tf timer_interface and message fillter
365  rclcpp::CallbackGroup::SharedPtr callback_group_;
366  rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
367  std::unique_ptr<nav2_util::NodeThread> executor_thread_;
368 
369  // Transform listener
370  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
371  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
372 
373  std::unique_ptr<LayeredCostmap> layered_costmap_{nullptr};
374  std::string name_;
375  std::string parent_namespace_;
376 
380  void mapUpdateLoop(double frequency);
381  bool map_update_thread_shutdown_{false};
382  std::atomic<bool> stop_updates_{false};
383  std::atomic<bool> initialized_{false};
384  std::atomic<bool> stopped_{true};
385  std::mutex _dynamic_parameter_mutex;
386  std::unique_ptr<std::thread> map_update_thread_;
387  rclcpp::Time last_publish_{0, 0, RCL_ROS_TIME};
388  rclcpp::Duration publish_cycle_{1, 0};
389  pluginlib::ClassLoader<Layer> plugin_loader_{"nav2_costmap_2d", "nav2_costmap_2d::Layer"};
390 
394  void getParameters();
395  bool always_send_full_costmap_{false};
396  std::string footprint_;
397  float footprint_padding_{0};
398  std::string global_frame_;
399  int map_height_meters_{0};
400  double map_publish_frequency_{0};
401  double map_update_frequency_{0};
402  int map_width_meters_{0};
403  double origin_x_{0};
404  double origin_y_{0};
405  std::vector<std::string> default_plugins_;
406  std::vector<std::string> default_types_;
407  std::vector<std::string> plugin_names_;
408  std::vector<std::string> plugin_types_;
409  std::vector<std::string> filter_names_;
410  std::vector<std::string> filter_types_;
411  double resolution_{0};
412  std::string robot_base_frame_;
413  double robot_radius_;
414  bool rolling_window_{false};
415  bool track_unknown_space_{false};
418  double map_vis_z_{0};
419 
421 
422  // Derived parameters
423  bool use_radius_{false};
424  std::vector<geometry_msgs::msg::Point> unpadded_footprint_;
425  std::vector<geometry_msgs::msg::Point> padded_footprint_;
426 
427  // Services
428  rclcpp::Service<nav2_msgs::srv::GetCost>::SharedPtr get_cost_service_;
429  std::unique_ptr<ClearCostmapService> clear_costmap_service_;
430 
431  // Dynamic parameters handler
432  OnSetParametersCallbackHandle::SharedPtr dyn_params_handler;
433 
438  rcl_interfaces::msg::SetParametersResult
439  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
440 };
441 
442 } // namespace nav2_costmap_2d
443 
444 #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.
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 getCostCallback(const std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< nav2_msgs::srv::GetCost::Request > request, const std::shared_ptr< nav2_msgs::srv::GetCost::Response > response)
Get the cost at a point in 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: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:92