diff --git a/localization/pose2twist/CMakeLists.txt b/localization/pose2twist/CMakeLists.txt
index a2fbbddf7d120..2a586aa9cd049 100644
--- a/localization/pose2twist/CMakeLists.txt
+++ b/localization/pose2twist/CMakeLists.txt
@@ -4,11 +4,16 @@ project(pose2twist)
find_package(autoware_cmake REQUIRED)
autoware_package()
-ament_auto_add_executable(pose2twist
- src/pose2twist_node.cpp
+ament_auto_add_library(${PROJECT_NAME} SHARED
src/pose2twist_core.cpp
)
+rclcpp_components_register_node(${PROJECT_NAME}
+ PLUGIN "Pose2Twist"
+ EXECUTABLE ${PROJECT_NAME}_node
+ EXECUTOR SingleThreadedExecutor
+)
+
ament_auto_package(
INSTALL_TO_SHARE
launch
diff --git a/localization/pose2twist/include/pose2twist/pose2twist_core.hpp b/localization/pose2twist/include/pose2twist/pose2twist_core.hpp
index c2a39f7e2ed3d..459a62ea5cd13 100644
--- a/localization/pose2twist/include/pose2twist/pose2twist_core.hpp
+++ b/localization/pose2twist/include/pose2twist/pose2twist_core.hpp
@@ -24,7 +24,7 @@
class Pose2Twist : public rclcpp::Node
{
public:
- Pose2Twist();
+ explicit Pose2Twist(const rclcpp::NodeOptions & options);
~Pose2Twist() = default;
private:
diff --git a/localization/pose2twist/launch/pose2twist.launch.xml b/localization/pose2twist/launch/pose2twist.launch.xml
index a0fae57a163e6..57a41dbfcf017 100644
--- a/localization/pose2twist/launch/pose2twist.launch.xml
+++ b/localization/pose2twist/launch/pose2twist.launch.xml
@@ -2,7 +2,7 @@
-
+
diff --git a/localization/pose2twist/package.xml b/localization/pose2twist/package.xml
index 16c49bb51c218..07e445c72978c 100644
--- a/localization/pose2twist/package.xml
+++ b/localization/pose2twist/package.xml
@@ -19,6 +19,7 @@
geometry_msgs
rclcpp
+ rclcpp_components
tf2_geometry_msgs
tier4_debug_msgs
diff --git a/localization/pose2twist/src/pose2twist_core.cpp b/localization/pose2twist/src/pose2twist_core.cpp
index a321a06122816..4b98ec6c81ad4 100644
--- a/localization/pose2twist/src/pose2twist_core.cpp
+++ b/localization/pose2twist/src/pose2twist_core.cpp
@@ -24,7 +24,7 @@
#include
#include
-Pose2Twist::Pose2Twist() : Node("pose2twist_core")
+Pose2Twist::Pose2Twist(const rclcpp::NodeOptions & options) : rclcpp::Node("pose2twist", options)
{
using std::placeholders::_1;
@@ -129,3 +129,6 @@ void Pose2Twist::callbackPose(geometry_msgs::msg::PoseStamped::SharedPtr pose_ms
angular_z_msg.data = twist_msg.twist.angular.z;
angular_z_pub_->publish(angular_z_msg);
}
+
+#include
+RCLCPP_COMPONENTS_REGISTER_NODE(Pose2Twist)
diff --git a/localization/pose2twist/src/pose2twist_node.cpp b/localization/pose2twist/src/pose2twist_node.cpp
deleted file mode 100644
index 81f98461ecffd..0000000000000
--- a/localization/pose2twist/src/pose2twist_node.cpp
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright 2015-2019 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 "pose2twist/pose2twist_core.hpp"
-
-#include
-
-#include
-
-int main(int argc, char ** argv)
-{
- rclcpp::init(argc, argv);
-
- rclcpp::spin(std::make_shared());
- rclcpp::shutdown();
-
- return 0;
-}