diff --git a/nav2_dwb_controller/dwb_core/include/dwb_core/publisher.hpp b/nav2_dwb_controller/dwb_core/include/dwb_core/publisher.hpp
index 2dca4ed1b03f56920146beaf1fe1685834f4d496..cb8867d9ed88184c6a5eeffab90671d756bba344 100644
--- a/nav2_dwb_controller/dwb_core/include/dwb_core/publisher.hpp
+++ b/nav2_dwb_controller/dwb_core/include/dwb_core/publisher.hpp
@@ -42,7 +42,6 @@
 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
 #include "dwb_core/trajectory_critic.hpp"
 #include "dwb_msgs/msg/local_plan_evaluation.hpp"
-#include "nav2_util/lifecycle_helper_interface.hpp"
 #include "nav_msgs/msg/path.hpp"
 #include "rclcpp/rclcpp.hpp"
 #include "sensor_msgs/msg/point_cloud2.hpp"
diff --git a/nav2_map_server/include/nav2_map_server/map_server.hpp b/nav2_map_server/include/nav2_map_server/map_server.hpp
index 77baf863c7980161a196249173bfa872eee64eea..aaaece071beeda21a69a03e21179435a00c45249 100644
--- a/nav2_map_server/include/nav2_map_server/map_server.hpp
+++ b/nav2_map_server/include/nav2_map_server/map_server.hpp
@@ -17,7 +17,6 @@
 
 #include <memory>
 #include "nav2_util/lifecycle_node.hpp"
-#include "nav2_util/lifecycle_helper_interface.hpp"
 
 namespace nav2_map_server
 {
@@ -38,7 +37,7 @@ protected:
   nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & state) override;
 
   // The map loader that will actually do the work
-  std::unique_ptr<nav2_util::LifecycleHelperInterface> map_loader_;
+  std::unique_ptr<rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface> map_loader_;
 };
 
 }  // namespace nav2_map_server
diff --git a/nav2_map_server/include/nav2_map_server/occ_grid_loader.hpp b/nav2_map_server/include/nav2_map_server/occ_grid_loader.hpp
index 23206e5719fec13cbd445f2b0cc28ac1ad85dc95..e29a0ac0f3d6fdf7479cf9e0b63c4103723aa00e 100644
--- a/nav2_map_server/include/nav2_map_server/occ_grid_loader.hpp
+++ b/nav2_map_server/include/nav2_map_server/occ_grid_loader.hpp
@@ -28,7 +28,7 @@
 
 namespace nav2_map_server
 {
-class OccGridLoader : public nav2_util::LifecycleHelperInterface
+class OccGridLoader : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
 {
 public:
   OccGridLoader(rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::string & yaml_filename);
diff --git a/nav2_util/include/nav2_util/lifecycle_helper_interface.hpp b/nav2_util/include/nav2_util/lifecycle_helper_interface.hpp
deleted file mode 100644
index 06285a8bf7425127c323d0a7a5d0f5c89a62d774..0000000000000000000000000000000000000000
--- a/nav2_util/include/nav2_util/lifecycle_helper_interface.hpp
+++ /dev/null
@@ -1,43 +0,0 @@
-// Copyright (c) 2019 Intel Corporation
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-//     http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef NAV2_UTIL__LIFECYCLE_HELPER_INTERFACE_HPP_
-#define NAV2_UTIL__LIFECYCLE_HELPER_INTERFACE_HPP_
-
-#include "rclcpp_lifecycle/lifecycle_node.hpp"
-
-namespace nav2_util
-{
-
-using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
-
-// A lifecycle interface minus onError and onShutdown, which are only relevant for nodes. This
-// has been proposed for rclcpp: https://github.com/ros2/rclcpp/issues/654 and hopefully can be
-// added as rclcpp_lifecycle::LifecycleHelperInterface. If not, we can remove this interface
-// and just use the whole rclcpp_lifecycle::LifecycleNodeInterface.
-
-class LifecycleHelperInterface
-{
-public:
-  virtual ~LifecycleHelperInterface() {}
-
-  virtual CallbackReturn on_configure(const rclcpp_lifecycle::State & state) = 0;
-  virtual CallbackReturn on_activate(const rclcpp_lifecycle::State & state) = 0;
-  virtual CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) = 0;
-  virtual CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) = 0;
-};
-
-}  // namespace nav2_util
-
-#endif  // NAV2_UTIL__LIFECYCLE_HELPER_INTERFACE_HPP_
diff --git a/nav2_util/include/nav2_util/lifecycle_node.hpp b/nav2_util/include/nav2_util/lifecycle_node.hpp
index 3182f80cd37a5a2df2fbb94e39690dd623fa1b22..745d7454478fd4b5b71ec60c88e9983eb2c2131a 100644
--- a/nav2_util/include/nav2_util/lifecycle_node.hpp
+++ b/nav2_util/include/nav2_util/lifecycle_node.hpp
@@ -19,7 +19,6 @@
 #include <string>
 #include <thread>
 
-#include "nav2_util/lifecycle_helper_interface.hpp"
 #include "nav2_util/node_thread.hpp"
 #include "rclcpp_lifecycle/lifecycle_node.hpp"
 #include "rclcpp/rclcpp.hpp"
@@ -27,6 +26,8 @@
 namespace nav2_util
 {
 
+using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
+
 // The following is a temporary wrapper for rclcpp_lifecycle::LifecycleNode. This class
 // adds the optional creation of an rclcpp::Node that can be used by derived classes
 // to interface to classes, such as MessageFilter and TransformListener, that don't yet