diff --git a/autoware_iv_external_api_adaptor/package.xml b/autoware_iv_external_api_adaptor/package.xml
index 23a83de..23b9548 100644
--- a/autoware_iv_external_api_adaptor/package.xml
+++ b/autoware_iv_external_api_adaptor/package.xml
@@ -11,7 +11,7 @@
autoware_cmake
autoware_adapi_specs
- autoware_component_interface_specs
+ autoware_component_interface_specs_universe
autoware_component_interface_utils
autoware_control_msgs
autoware_external_api_msgs
diff --git a/autoware_iv_external_api_adaptor/src/initial_pose.cpp b/autoware_iv_external_api_adaptor/src/initial_pose.cpp
index 726ef3c..5ef478f 100644
--- a/autoware_iv_external_api_adaptor/src/initial_pose.cpp
+++ b/autoware_iv_external_api_adaptor/src/initial_pose.cpp
@@ -61,9 +61,9 @@ void InitialPose::setInitializePose(
const tier4_external_api_msgs::srv::InitializePose::Response::SharedPtr response)
{
const auto req = std::make_shared<
- autoware::component_interface_specs::localization::Initialize::Service::Request>();
+ autoware::component_interface_specs_universe::localization::Initialize::Service::Request>();
req->method =
- autoware::component_interface_specs::localization::Initialize::Service::Request::AUTO;
+ autoware::component_interface_specs_universe::localization::Initialize::Service::Request::AUTO;
req->pose_with_covariance.push_back(request->pose);
req->pose_with_covariance.back().pose.covariance = particle_covariance;
@@ -80,9 +80,9 @@ void InitialPose::setInitializePoseAuto(
const tier4_external_api_msgs::srv::InitializePoseAuto::Response::SharedPtr response)
{
const auto req = std::make_shared<
- autoware::component_interface_specs::localization::Initialize::Service::Request>();
+ autoware::component_interface_specs_universe::localization::Initialize::Service::Request>();
req->method =
- autoware::component_interface_specs::localization::Initialize::Service::Request::AUTO;
+ autoware::component_interface_specs_universe::localization::Initialize::Service::Request::AUTO;
try {
const auto res = cli_localization_initialize_->call(req, initial_pose_timeout);
diff --git a/autoware_iv_external_api_adaptor/src/initial_pose.hpp b/autoware_iv_external_api_adaptor/src/initial_pose.hpp
index 93ea21d..1055ab8 100644
--- a/autoware_iv_external_api_adaptor/src/initial_pose.hpp
+++ b/autoware_iv_external_api_adaptor/src/initial_pose.hpp
@@ -15,7 +15,7 @@
#ifndef INITIAL_POSE_HPP_
#define INITIAL_POSE_HPP_
-#include
+#include
#include
#include
#include
@@ -40,7 +40,7 @@ class InitialPose : public rclcpp::Node
tier4_api_utils::Service::SharedPtr srv_set_initialize_pose_;
tier4_api_utils::Service::SharedPtr srv_set_initialize_pose_auto_;
autoware::component_interface_utils::Client<
- autoware::component_interface_specs::localization::Initialize>::SharedPtr
+ autoware::component_interface_specs_universe::localization::Initialize>::SharedPtr
cli_localization_initialize_;
// ros callback