diff --git a/nav2_core/include/nav2_core/global_planner.hpp b/nav2_core/include/nav2_core/global_planner.hpp
index 50aa406295f4f0214900c53e18540a8d948f9d8a..ac31d92d4c5915e2c4db7fcaea97592a4c6b18d4 100644
--- a/nav2_core/include/nav2_core/global_planner.hpp
+++ b/nav2_core/include/nav2_core/global_planner.hpp
@@ -46,9 +46,9 @@ public:
    * @param  tf A pointer to a TF buffer
    * @param  costmap_ros A pointer to the costmap
    */
-  virtual void configure(nav2_util::LifecycleNode::SharedPtr parent,
+  virtual void configure(rclcpp_lifecycle::LifecycleNode::SharedPtr parent,
     std::string name, tf2_ros::Buffer * tf,
-    nav2_costmap_2d::Costmap2DROS * costmap_ros) = 0;
+    std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) = 0;
 
   /**
    * @brief Method to cleanup resources used on shutdown.
diff --git a/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp b/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp
index 1e5b0d10b1df66e96461faa124a6565263e5926e..a9a57d025988a6d238d85aa5ad05b1b06da96311 100644
--- a/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp
+++ b/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp
@@ -42,9 +42,9 @@ public:
 
   // plugin configure
   void configure(
-    nav2_util::LifecycleNode::SharedPtr parent,
+    rclcpp_lifecycle::LifecycleNode::SharedPtr parent,
     std::string name, tf2_ros::Buffer * tf,
-    nav2_costmap_2d::Costmap2DROS * costmap_ros) override;
+    std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
 
   // plugin cleanup
   void cleanup() override;
diff --git a/nav2_navfn_planner/src/navfn_planner.cpp b/nav2_navfn_planner/src/navfn_planner.cpp
index 5f327a5ce4c41ae7a734cdc32c11173c416295cc..590ea673ad14e288c6f2953dca9d6b1f639e4069 100644
--- a/nav2_navfn_planner/src/navfn_planner.cpp
+++ b/nav2_navfn_planner/src/navfn_planner.cpp
@@ -53,9 +53,9 @@ NavfnPlanner::~NavfnPlanner()
 
 void
 NavfnPlanner::configure(
-  nav2_util::LifecycleNode::SharedPtr parent,
+  rclcpp_lifecycle::LifecycleNode::SharedPtr parent,
   std::string name, tf2_ros::Buffer * tf,
-  nav2_costmap_2d::Costmap2DROS * costmap_ros)
+  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
 {
   node_ = parent;
   tf_ = tf;
diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp
index e74bb4f05f2f2177ad4ff73d37ecb674a36c912a..573d5f80c03511c9dac5e389ea13b7255c1416da 100644
--- a/nav2_planner/src/planner_server.cpp
+++ b/nav2_planner/src/planner_server.cpp
@@ -88,7 +88,7 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & state)
     RCLCPP_INFO(get_logger(), "Created global planner plugin %s",
       planner_plugin_name_.c_str());
     planner_->configure(node,
-      gp_loader_.getName(planner_plugin_name_), tf_.get(), costmap_ros_.get());
+      gp_loader_.getName(planner_plugin_name_), tf_.get(), costmap_ros_);
   } catch (const pluginlib::PluginlibException & ex) {
     RCLCPP_FATAL(get_logger(), "Failed to create global planner. Exception: %s",
       ex.what());