From 9a62d5a617bfb65ca47e80459734d0c962ca2711 Mon Sep 17 00:00:00 2001 From: stevemacenski Date: Fri, 11 Oct 2019 17:32:45 -0700 Subject: [PATCH] convert candidate shared ptrs to unique ptrs --- .../include/nav2_controller/nav2_controller.hpp | 2 +- nav2_controller/src/nav2_controller.cpp | 2 +- nav2_recoveries/include/nav2_recoveries/recovery.hpp | 8 ++++---- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/nav2_controller/include/nav2_controller/nav2_controller.hpp b/nav2_controller/include/nav2_controller/nav2_controller.hpp index d484d40cf5b..05835ce86c4 100644 --- a/nav2_controller/include/nav2_controller/nav2_controller.hpp +++ b/nav2_controller/include/nav2_controller/nav2_controller.hpp @@ -71,7 +71,7 @@ class ControllerServer : public nav2_util::LifecycleNode std::unique_ptr costmap_thread_; // Publishers and subscribers - std::shared_ptr odom_sub_; + std::unique_ptr odom_sub_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr vel_publisher_; // Local Planner Plugin diff --git a/nav2_controller/src/nav2_controller.cpp b/nav2_controller/src/nav2_controller.cpp index 06ea009b709..0207ef3403a 100644 --- a/nav2_controller/src/nav2_controller.cpp +++ b/nav2_controller/src/nav2_controller.cpp @@ -85,7 +85,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) get_parameter("controller_frequency", controller_frequency_); RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_); - odom_sub_ = std::make_shared(node); + odom_sub_ = std::make_unique(node); vel_publisher_ = create_publisher("/cmd_vel", 1); // Create the action server that we implement with our followPath method diff --git a/nav2_recoveries/include/nav2_recoveries/recovery.hpp b/nav2_recoveries/include/nav2_recoveries/recovery.hpp index 808629a65ca..e2fcf186aae 100644 --- a/nav2_recoveries/include/nav2_recoveries/recovery.hpp +++ b/nav2_recoveries/include/nav2_recoveries/recovery.hpp @@ -104,10 +104,10 @@ class Recovery : public nav2_core::Recovery action_server_ = std::make_unique(node_, recovery_name_, std::bind(&Recovery::execute, this)); - costmap_sub_ = std::make_shared( + costmap_sub_ = std::make_unique( node_, costmap_topic); - footprint_sub_ = std::make_shared( + footprint_sub_ = std::make_unique( node_, footprint_topic); collision_checker_ = std::make_unique( @@ -147,8 +147,8 @@ class Recovery : public nav2_core::Recovery std::shared_ptr tf_; std::unique_ptr action_server_; - std::shared_ptr costmap_sub_; - std::shared_ptr footprint_sub_; + std::unique_ptr costmap_sub_; + std::unique_ptr footprint_sub_; std::unique_ptr collision_checker_; double cycle_frequency_; double enabled_;