diff --git a/nav2_core/include/nav2_core/global_planner.hpp b/nav2_core/include/nav2_core/global_planner.hpp
index c72d2cc4e4a471cb72ad139dd1574380c59482e0..323f414ac52a478ebdda7bdd0e76ca1d4c3b4fed 100644
--- a/nav2_core/include/nav2_core/global_planner.hpp
+++ b/nav2_core/include/nav2_core/global_planner.hpp
@@ -63,7 +63,7 @@ public:
* @param tf A pointer to a TF buffer
* @param costmap_ros A pointer to the costmap
*/
- virtual void configure(const rclcpp::Node * parent,
+ virtual void configure(const rclcpp::LifecycleNode * parent,
const std::string & name, tf2_ros::Buffer * tf,
nav2_costmap_2d::Costmap2DROS * costmap_ros) = 0;
diff --git a/nav2_core/include/nav2_core/recovery.hpp b/nav2_core/include/nav2_core/recovery.hpp
index ca02f3c20ee49c506c6333f50322fbaec72f8bb7..80d67e27a01e731cd4301438d4611050180732c4 100644
--- a/nav2_core/include/nav2_core/recovery.hpp
+++ b/nav2_core/include/nav2_core/recovery.hpp
@@ -60,7 +60,7 @@ public:
* @param tf A pointer to a TF buffer
* @param costmap_ros A pointer to the costmap
*/
- virtual void configure(const rclcpp::Node * parent,
+ virtual void configure(const rclcpp::LifecycleNode * parent,
const std::string & name, tf2_ros::Buffer * tf) = 0;
/**