diff --git a/localization/pose_instability_detector/CMakeLists.txt b/localization/pose_instability_detector/CMakeLists.txt
index 5270df636d791..c6f94ab7df16e 100644
--- a/localization/pose_instability_detector/CMakeLists.txt
+++ b/localization/pose_instability_detector/CMakeLists.txt
@@ -4,14 +4,19 @@ project(pose_instability_detector)
 find_package(autoware_cmake REQUIRED)
 autoware_package()
 
-ament_auto_add_executable(pose_instability_detector
-  src/main.cpp
+ament_auto_add_library(${PROJECT_NAME} SHARED
   src/pose_instability_detector.cpp
 )
 
+rclcpp_components_register_node(${PROJECT_NAME}
+  PLUGIN "PoseInstabilityDetector"
+  EXECUTABLE ${PROJECT_NAME}_node
+  EXECUTOR SingleThreadedExecutor
+)
+
 if(BUILD_TESTING)
   find_package(ament_cmake_gtest REQUIRED)
-  ament_auto_add_gtest(test_pose_instability_detector
+  ament_auto_add_gtest(test_${PROJECT_NAME}
     test/test.cpp
     src/pose_instability_detector.cpp
   )
@@ -19,6 +24,6 @@ endif()
 
 ament_auto_package(
   INSTALL_TO_SHARE
-    launch
-    config
+  launch
+  config
 )
diff --git a/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml b/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml
index 4a390ee2854d7..5ebe7d7e429e0 100644
--- a/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml
+++ b/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml
@@ -6,7 +6,7 @@
   <arg name="input_odometry" default="~/input/odometry"/>
   <arg name="input_twist" default="~/input/twist"/>
 
-  <node pkg="pose_instability_detector" exec="pose_instability_detector" name="$(var node_name)" output="log">
+  <node pkg="pose_instability_detector" exec="pose_instability_detector_node" name="$(var node_name)" output="both">
     <remap from="~/input/odometry" to="$(var input_odometry)"/>
     <remap from="~/input/twist" to="$(var input_twist)"/>
     <param from="$(var param_file)"/>
diff --git a/localization/pose_instability_detector/package.xml b/localization/pose_instability_detector/package.xml
index bf57e5589b747..d658d1c2d437f 100644
--- a/localization/pose_instability_detector/package.xml
+++ b/localization/pose_instability_detector/package.xml
@@ -22,6 +22,7 @@
   <depend>geometry_msgs</depend>
   <depend>nav_msgs</depend>
   <depend>rclcpp</depend>
+  <depend>rclcpp_components</depend>
   <depend>tf2</depend>
   <depend>tf2_geometry_msgs</depend>
   <depend>tier4_autoware_utils</depend>
diff --git a/localization/pose_instability_detector/src/main.cpp b/localization/pose_instability_detector/src/main.cpp
deleted file mode 100644
index 34e679e86730f..0000000000000
--- a/localization/pose_instability_detector/src/main.cpp
+++ /dev/null
@@ -1,26 +0,0 @@
-// Copyright 2023- Autoware Foundation
-//
-// 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.
-
-#include "pose_instability_detector.hpp"
-
-#include <rclcpp/rclcpp.hpp>
-
-int main(int argc, char ** argv)
-{
-  rclcpp::init(argc, argv);
-  auto pose_instability_detector = std::make_shared<PoseInstabilityDetector>();
-  rclcpp::spin(pose_instability_detector);
-  rclcpp::shutdown();
-  return 0;
-}
diff --git a/localization/pose_instability_detector/src/pose_instability_detector.cpp b/localization/pose_instability_detector/src/pose_instability_detector.cpp
index afb7d6e007db2..c2bce6a3db288 100644
--- a/localization/pose_instability_detector/src/pose_instability_detector.cpp
+++ b/localization/pose_instability_detector/src/pose_instability_detector.cpp
@@ -23,7 +23,7 @@
 #include <string>
 
 PoseInstabilityDetector::PoseInstabilityDetector(const rclcpp::NodeOptions & options)
-: Node("pose_instability_detector", options),
+: rclcpp::Node("pose_instability_detector", options),
   threshold_diff_position_x_(this->declare_parameter<double>("threshold_diff_position_x")),
   threshold_diff_position_y_(this->declare_parameter<double>("threshold_diff_position_y")),
   threshold_diff_position_z_(this->declare_parameter<double>("threshold_diff_position_z")),
@@ -174,3 +174,6 @@ void PoseInstabilityDetector::callback_timer()
   prev_odometry_ = latest_odometry_;
   twist_buffer_.clear();
 }
+
+#include <rclcpp_components/register_node_macro.hpp>
+RCLCPP_COMPONENTS_REGISTER_NODE(PoseInstabilityDetector)