Skip to content

Commit

Permalink
use shared ptr in layer
Browse files Browse the repository at this point in the history
  • Loading branch information
bpwilcox committed Dec 4, 2019
1 parent 94a8d37 commit a76e5fa
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 4 deletions.
4 changes: 2 additions & 2 deletions nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ class Layer // TODO(mjeronimo): public nav2_util::LifecycleHelperInterface
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() {}
Expand Down Expand Up @@ -137,7 +137,7 @@ class Layer // TODO(mjeronimo): public nav2_util::LifecycleHelperInterface
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
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
}
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/src/layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit a76e5fa

Please sign in to comment.