diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp index c63fd8beeae2304ba6f10b64273b127ec93e414c..9819eb38d6ae59b1459326b2297e6d68131c8fc1 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp @@ -66,7 +66,7 @@ public: nav2_util::LifecycleNode::SharedPtr node, rclcpp::Node::SharedPtr client_node, rclcpp::Node::SharedPtr rclcpp_node, - nav2_util::ParameterEventsSubscriber * param_subscriber = nullptr); + std::shared_ptr<nav2_util::ParameterEventsSubscriber> param_subscriber = nullptr); virtual void deactivate() {} /** @brief Stop publishers. */ virtual void activate() {} /** @brief Restart publishers if they've been stopped. */ virtual void reset() {} @@ -137,7 +137,7 @@ protected: nav2_util::LifecycleNode::SharedPtr node_; rclcpp::Node::SharedPtr client_node_; rclcpp::Node::SharedPtr rclcpp_node_; - nav2_util::ParameterEventsSubscriber * param_subscriber_; + std::shared_ptr<nav2_util::ParameterEventsSubscriber> param_subscriber_; std::vector<nav2_util::ParameterEventsCallbackHandle::SharedPtr> callback_handles_; /** @brief This is called at the end of initialize(). Override to diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 9a6f195e39938d46f2bb99573f0920b30b1a86e1..29e8fa300097059ef1d799d55a23d8ba4268c3a4 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -148,7 +148,7 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/) // TODO(mjeronimo): instead of get(), use a shared ptr plugin->initialize(layered_costmap_, plugin_names_[i], tf_buffer_.get(), - shared_from_this(), client_node_, rclcpp_node_, param_subscriber_.get()); + shared_from_this(), client_node_, rclcpp_node_, param_subscriber_); RCLCPP_INFO(get_logger(), "Initialized plugin \"%s\"", plugin_names_[i].c_str()); } diff --git a/nav2_costmap_2d/src/layer.cpp b/nav2_costmap_2d/src/layer.cpp index 571b4a5b18bb7c0f7500b2c9e914be37b9ee1270..c51e43f8db1578d11ddac86b2bdf18afc9500566 100644 --- a/nav2_costmap_2d/src/layer.cpp +++ b/nav2_costmap_2d/src/layer.cpp @@ -50,7 +50,7 @@ Layer::initialize( nav2_util::LifecycleNode::SharedPtr node, rclcpp::Node::SharedPtr client_node, rclcpp::Node::SharedPtr rclcpp_node, - nav2_util::ParameterEventsSubscriber * param_subscriber) + std::shared_ptr<nav2_util::ParameterEventsSubscriber> param_subscriber) { layered_costmap_ = parent; name_ = name;