37 #ifndef NAV2_COSTMAP_2D__LAYER_HPP_
38 #define NAV2_COSTMAP_2D__LAYER_HPP_
42 #include <unordered_set>
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"
77 const nav2_util::LifecycleNode::WeakPtr & node,
78 rclcpp::CallbackGroup::SharedPtr callback_group);
101 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
112 int min_i,
int min_j,
int max_i,
int max_j) = 0;
149 const std::vector<geometry_msgs::msg::Point> &
getFootprint()
const;
153 const std::string & param_name,
154 const rclcpp::ParameterValue & value);
157 const std::string & param_name,
158 const rclcpp::ParameterType & param_type);
162 std::string
getFullName(
const std::string & param_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")};
204 std::unordered_set<std::string> local_params_;
207 std::vector<geometry_msgs::msg::Point> footprint_spec_;
A 2D costmap provides a mapping between points in the world and their associated "costs".
Abstract class for layered costmap plugin implementations.
virtual void onFootprintChanged()
LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint())....
virtual void activate()
Restart publishers if they've been stopped.
std::string joinWithParentNamespace(const std::string &topic)
bool hasParameter(const std::string ¶m_name)
Convenience functions for declaring ROS parameters.
virtual void deactivate()
Stop publishers.
virtual bool isClearable()=0
If clearing operations should be processed on this layer or not.
void declareParameter(const std::string ¶m_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
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,...
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
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.
virtual ~Layer()
A destructor.
bool isEnabled() const
Gets whether the layer is enabled.
const std::vector< geometry_msgs::msg::Point > & getFootprint() const
Convenience function for layered_costmap_->getFootprint().
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.
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 ¶m_name)
Convenience functions for declaring ROS parameters.
std::string getName() const
Get the name of the costmap layer.
Instantiates different layer plugins and aggregates them into one score.