diff --git a/system/default_ad_api_helpers/ad_api_adaptors/CMakeLists.txt b/system/default_ad_api_helpers/ad_api_adaptors/CMakeLists.txt index 35cb599995b31..c14f71571d272 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/CMakeLists.txt +++ b/system/default_ad_api_helpers/ad_api_adaptors/CMakeLists.txt @@ -4,12 +4,21 @@ project(ad_api_adaptors) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(initial_pose_adaptor +ament_auto_add_library(${PROJECT_NAME} SHARED src/initial_pose_adaptor.cpp + src/routing_adaptor.cpp ) -ament_auto_add_executable(routing_adaptor - src/routing_adaptor.cpp +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "ad_api_adaptors::InitialPoseAdaptor" + EXECUTABLE initial_pose_adaptor_node + EXECUTOR MultiThreadedExecutor +) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "ad_api_adaptors::RoutingAdaptor" + EXECUTABLE routing_adaptor_node + EXECUTOR SingleThreadedExecutor ) ament_auto_package(INSTALL_TO_SHARE config launch) diff --git a/system/default_ad_api_helpers/ad_api_adaptors/launch/rviz_adaptors.launch.xml b/system/default_ad_api_helpers/ad_api_adaptors/launch/rviz_adaptors.launch.xml index 4d00e254e78d5..855f57345ed15 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/launch/rviz_adaptors.launch.xml +++ b/system/default_ad_api_helpers/ad_api_adaptors/launch/rviz_adaptors.launch.xml @@ -3,7 +3,7 @@ - + @@ -12,7 +12,7 @@ - + diff --git a/system/default_ad_api_helpers/ad_api_adaptors/package.xml b/system/default_ad_api_helpers/ad_api_adaptors/package.xml index 785ff58db1f81..b070131f1d567 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/package.xml +++ b/system/default_ad_api_helpers/ad_api_adaptors/package.xml @@ -17,6 +17,7 @@ component_interface_utils map_height_fitter rclcpp + rclcpp_components ament_lint_auto autoware_lint_common diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp b/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp index 5d34653244ea2..f3c0ab9213656 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp +++ b/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp @@ -34,7 +34,8 @@ std::array get_covariance_parameter(rclcpp::Node * node, const std:: return array; } -InitialPoseAdaptor::InitialPoseAdaptor() : Node("initial_pose_adaptor"), fitter_(this) +InitialPoseAdaptor::InitialPoseAdaptor(const rclcpp::NodeOptions & options) +: Node("initial_pose_adaptor", options), fitter_(this) { rviz_particle_covariance_ = get_covariance_parameter(this, "initial_pose_particle_covariance"); sub_initial_pose_ = create_subscription( @@ -61,13 +62,5 @@ void InitialPoseAdaptor::on_initial_pose(const PoseWithCovarianceStamped::ConstS } // namespace ad_api_adaptors -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - rclcpp::executors::MultiThreadedExecutor executor; - auto node = std::make_shared(); - executor.add_node(node); - executor.spin(); - executor.remove_node(node); - rclcpp::shutdown(); -} +#include +RCLCPP_COMPONENTS_REGISTER_NODE(ad_api_adaptors::InitialPoseAdaptor) diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp b/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp index 0531afd55ac21..340bc3b0a3058 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp +++ b/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp @@ -28,7 +28,7 @@ namespace ad_api_adaptors class InitialPoseAdaptor : public rclcpp::Node { public: - InitialPoseAdaptor(); + explicit InitialPoseAdaptor(const rclcpp::NodeOptions & options); private: using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.cpp b/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.cpp index 7151902a972d6..18421c976cf41 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.cpp +++ b/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.cpp @@ -19,7 +19,8 @@ namespace ad_api_adaptors { -RoutingAdaptor::RoutingAdaptor() : Node("routing_adaptor") +RoutingAdaptor::RoutingAdaptor(const rclcpp::NodeOptions & options) +: Node("routing_adaptor", options) { using std::placeholders::_1; @@ -110,13 +111,5 @@ void RoutingAdaptor::on_reroute(const PoseStamped::ConstSharedPtr pose) } // namespace ad_api_adaptors -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor executor; - auto node = std::make_shared(); - executor.add_node(node); - executor.spin(); - executor.remove_node(node); - rclcpp::shutdown(); -} +#include +RCLCPP_COMPONENTS_REGISTER_NODE(ad_api_adaptors::RoutingAdaptor) diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp b/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp index 4040ee37ead3e..877d705825733 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp +++ b/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp @@ -29,7 +29,7 @@ namespace ad_api_adaptors class RoutingAdaptor : public rclcpp::Node { public: - RoutingAdaptor(); + explicit RoutingAdaptor(const rclcpp::NodeOptions & options); private: using PoseStamped = geometry_msgs::msg::PoseStamped;