30 #include "nav2_costmap_2d/layer.hpp"
34 #include "nav2_util/node_utils.hpp"
40 : layered_costmap_(nullptr),
52 const nav2_util::LifecycleNode::WeakPtr & node,
53 rclcpp::CallbackGroup::SharedPtr callback_group)
55 layered_costmap_ = parent;
59 callback_group_ = callback_group;
61 auto node_shared_ptr = node_.lock();
62 logger_ = node_shared_ptr->get_logger();
63 clock_ = node_shared_ptr->get_clock();
69 const std::vector<geometry_msgs::msg::Point> &
77 const std::string & param_name,
78 const rclcpp::ParameterValue & value)
80 auto node = node_.lock();
82 throw std::runtime_error{
"Failed to lock node"};
84 local_params_.insert(param_name);
85 nav2_util::declare_parameter_if_not_declared(
91 const std::string & param_name,
92 const rclcpp::ParameterType & param_type)
94 auto node = node_.lock();
96 throw std::runtime_error{
"Failed to lock node"};
98 local_params_.insert(param_name);
99 nav2_util::declare_parameter_if_not_declared(
106 auto node = node_.lock();
108 throw std::runtime_error{
"Failed to lock node"};
110 return node->has_parameter(
getFullName(param_name));
116 return std::string(name_ +
"." + param_name);
bool hasParameter(const std::string ¶m_name)
Convenience functions for declaring ROS parameters.
void declareParameter(const std::string ¶m_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
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.
const std::vector< geometry_msgs::msg::Point > & getFootprint() const
Convenience function for layered_costmap_->getFootprint().
std::string getFullName(const std::string ¶m_name)
Convenience functions for declaring ROS parameters.
Instantiates different layer plugins and aggregates them into one score.
const std::vector< geometry_msgs::msg::Point > & getFootprint()
Returns the latest footprint stored with setFootprint().