diff --git a/nav2_controller/include/nav2_controller/nav2_controller.hpp b/nav2_controller/include/nav2_controller/nav2_controller.hpp
index d484d40cf5baba51d180f586cfc68282aa64e6d6..05835ce86c4df635088962becdc1c774cf2577e9 100644
--- a/nav2_controller/include/nav2_controller/nav2_controller.hpp
+++ b/nav2_controller/include/nav2_controller/nav2_controller.hpp
@@ -71,7 +71,7 @@ protected:
   std::unique_ptr<std::thread> costmap_thread_;
 
   // Publishers and subscribers
-  std::shared_ptr<nav_2d_utils::OdomSubscriber> odom_sub_;
+  std::unique_ptr<nav_2d_utils::OdomSubscriber> odom_sub_;
   rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::Twist>::SharedPtr vel_publisher_;
 
   // Local Planner Plugin
diff --git a/nav2_controller/src/nav2_controller.cpp b/nav2_controller/src/nav2_controller.cpp
index 06ea009b7094f104842ccb4795a3bc764b2ad064..0207ef3403a6cb322668d7aaa9034196c738355f 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<nav_2d_utils::OdomSubscriber>(node);
+  odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node);
   vel_publisher_ = create_publisher<geometry_msgs::msg::Twist>("/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 808629a65ca77155343fa5a7ffa415f8b765618e..e2fcf186aae5d8c5c95b97c20e59f4cc32bbe0a4 100644
--- a/nav2_recoveries/include/nav2_recoveries/recovery.hpp
+++ b/nav2_recoveries/include/nav2_recoveries/recovery.hpp
@@ -104,10 +104,10 @@ public:
     action_server_ = std::make_unique<ActionServer>(node_, recovery_name_,
         std::bind(&Recovery::execute, this));
 
-    costmap_sub_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(
+    costmap_sub_ = std::make_unique<nav2_costmap_2d::CostmapSubscriber>(
       node_, costmap_topic);
 
-    footprint_sub_ = std::make_shared<nav2_costmap_2d::FootprintSubscriber>(
+    footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
       node_, footprint_topic);
 
     collision_checker_ = std::make_unique<nav2_costmap_2d::CollisionChecker>(
@@ -147,8 +147,8 @@ protected:
   std::shared_ptr<tf2_ros::Buffer> tf_;
   std::unique_ptr<ActionServer> action_server_;
 
-  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
-  std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
+  std::unique_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
+  std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
   std::unique_ptr<nav2_costmap_2d::CollisionChecker> collision_checker_;
   double cycle_frequency_;
   double enabled_;