Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
layer.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: David V. Lu!!
36  *********************************************************************/
37 #ifndef NAV2_COSTMAP_2D__LAYER_HPP_
38 #define NAV2_COSTMAP_2D__LAYER_HPP_
39 
40 #include <string>
41 #include <vector>
42 #include <unordered_set>
43 
44 #include "tf2_ros/buffer.h"
45 #include "rclcpp/rclcpp.hpp"
46 #include "nav2_costmap_2d/costmap_2d.hpp"
47 #include "nav2_costmap_2d/layered_costmap.hpp"
48 #include "nav2_util/lifecycle_node.hpp"
49 
50 namespace nav2_costmap_2d
51 {
52 class LayeredCostmap;
53 
58 class Layer
59 {
60 public:
64  Layer();
68  virtual ~Layer() {}
69 
73  void initialize(
74  LayeredCostmap * parent,
75  std::string name,
76  tf2_ros::Buffer * tf,
77  const nav2_util::LifecycleNode::WeakPtr & node,
78  rclcpp::CallbackGroup::SharedPtr callback_group);
80  virtual void deactivate() {}
82  virtual void activate() {}
86  virtual void reset() = 0;
90  virtual bool isClearable() = 0;
91 
100  virtual void updateBounds(
101  double robot_x, double robot_y, double robot_yaw, double * min_x,
102  double * min_y,
103  double * max_x,
104  double * max_y) = 0;
105 
110  virtual void updateCosts(
111  Costmap2D & master_grid,
112  int min_i, int min_j, int max_i, int max_j) = 0;
113 
115  virtual void matchSize() {}
116 
120  virtual void onFootprintChanged() {}
122  std::string getName() const
123  {
124  return name_;
125  }
126 
137  bool isCurrent() const
138  {
139  return current_;
140  }
141 
143  bool isEnabled() const
144  {
145  return enabled_;
146  }
147 
149  const std::vector<geometry_msgs::msg::Point> & getFootprint() const;
150 
152  void declareParameter(
153  const std::string & param_name,
154  const rclcpp::ParameterValue & value);
156  void declareParameter(
157  const std::string & param_name,
158  const rclcpp::ParameterType & param_type);
160  bool hasParameter(const std::string & param_name);
162  std::string getFullName(const std::string & param_name);
163 
180  std::string joinWithParentNamespace(const std::string & topic);
181 
182 protected:
183  LayeredCostmap * layered_costmap_;
184  std::string name_;
185  tf2_ros::Buffer * tf_;
186  rclcpp::CallbackGroup::SharedPtr callback_group_;
187  rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
188  rclcpp::Clock::SharedPtr clock_;
189  rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")};
190 
196  virtual void onInitialize() {}
197 
198  bool current_;
199  // Currently this var is managed by subclasses.
200  // TODO(bpwilcox): make this managed by this class and/or container class.
201  bool enabled_;
202 
203  // Names of the parameters declared on the ROS node
204  std::unordered_set<std::string> local_params_;
205 
206 private:
207  std::vector<geometry_msgs::msg::Point> footprint_spec_;
208 };
209 
210 } // namespace nav2_costmap_2d
211 
212 #endif // NAV2_COSTMAP_2D__LAYER_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
Abstract class for layered costmap plugin implementations.
Definition: layer.hpp:59
virtual void onFootprintChanged()
LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint())....
Definition: layer.hpp:120
virtual void activate()
Restart publishers if they've been stopped.
Definition: layer.hpp:82
std::string joinWithParentNamespace(const std::string &topic)
Definition: layer.cpp:121
bool hasParameter(const std::string &param_name)
Convenience functions for declaring ROS parameters.
Definition: layer.cpp:104
virtual void deactivate()
Stop publishers.
Definition: layer.hpp:80
virtual bool isClearable()=0
If clearing operations should be processed on this layer or not.
void declareParameter(const std::string &param_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
Definition: layer.cpp:76
bool isCurrent() const
Check to make sure all the data in the layer is up to date. If the layer is not up to date,...
Definition: layer.hpp:137
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
Definition: layer.hpp:196
virtual void reset()=0
Reset this costmap.
void initialize(LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf, const nav2_util::LifecycleNode::WeakPtr &node, rclcpp::CallbackGroup::SharedPtr callback_group)
Initialization process of layer on startup.
Definition: layer.cpp:48
virtual ~Layer()
A destructor.
Definition: layer.hpp:68
bool isEnabled() const
Gets whether the layer is enabled.
Definition: layer.hpp:143
const std::vector< geometry_msgs::msg::Point > & getFootprint() const
Convenience function for layered_costmap_->getFootprint().
Definition: layer.cpp:70
Layer()
A constructor.
Definition: layer.cpp:39
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)=0
This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to up...
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
Definition: layer.hpp:115
virtual void updateCosts(Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)=0
Actually update the underlying costmap, only within the bounds calculated during UpdateBounds().
std::string getFullName(const std::string &param_name)
Convenience functions for declaring ROS parameters.
Definition: layer.cpp:114
std::string getName() const
Get the name of the costmap layer.
Definition: layer.hpp:122
Instantiates different layer plugins and aggregates them into one score.