Skip to content

Commit a76e5fa

Browse files
author
bpwilcox
committed
use shared ptr in layer
1 parent 94a8d37 commit a76e5fa

File tree

3 files changed

+4
-4
lines changed

3 files changed

+4
-4
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ class Layer // TODO(mjeronimo): public nav2_util::LifecycleHelperInterface
6666
nav2_util::LifecycleNode::SharedPtr node,
6767
rclcpp::Node::SharedPtr client_node,
6868
rclcpp::Node::SharedPtr rclcpp_node,
69-
nav2_util::ParameterEventsSubscriber * param_subscriber = nullptr);
69+
std::shared_ptr<nav2_util::ParameterEventsSubscriber> param_subscriber = nullptr);
7070
virtual void deactivate() {} /** @brief Stop publishers. */
7171
virtual void activate() {} /** @brief Restart publishers if they've been stopped. */
7272
virtual void reset() {}
@@ -137,7 +137,7 @@ class Layer // TODO(mjeronimo): public nav2_util::LifecycleHelperInterface
137137
nav2_util::LifecycleNode::SharedPtr node_;
138138
rclcpp::Node::SharedPtr client_node_;
139139
rclcpp::Node::SharedPtr rclcpp_node_;
140-
nav2_util::ParameterEventsSubscriber * param_subscriber_;
140+
std::shared_ptr<nav2_util::ParameterEventsSubscriber> param_subscriber_;
141141
std::vector<nav2_util::ParameterEventsCallbackHandle::SharedPtr> callback_handles_;
142142

143143
/** @brief This is called at the end of initialize(). Override to

nav2_costmap_2d/src/costmap_2d_ros.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -148,7 +148,7 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
148148

149149
// TODO(mjeronimo): instead of get(), use a shared ptr
150150
plugin->initialize(layered_costmap_, plugin_names_[i], tf_buffer_.get(),
151-
shared_from_this(), client_node_, rclcpp_node_, param_subscriber_.get());
151+
shared_from_this(), client_node_, rclcpp_node_, param_subscriber_);
152152

153153
RCLCPP_INFO(get_logger(), "Initialized plugin \"%s\"", plugin_names_[i].c_str());
154154
}

nav2_costmap_2d/src/layer.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ Layer::initialize(
5050
nav2_util::LifecycleNode::SharedPtr node,
5151
rclcpp::Node::SharedPtr client_node,
5252
rclcpp::Node::SharedPtr rclcpp_node,
53-
nav2_util::ParameterEventsSubscriber * param_subscriber)
53+
std::shared_ptr<nav2_util::ParameterEventsSubscriber> param_subscriber)
5454
{
5555
layered_costmap_ = parent;
5656
name_ = name;

0 commit comments

Comments
 (0)