diff --git a/autoware_iv_external_api_adaptor/package.xml b/autoware_iv_external_api_adaptor/package.xml
index 508da09..0a46882 100644
--- a/autoware_iv_external_api_adaptor/package.xml
+++ b/autoware_iv_external_api_adaptor/package.xml
@@ -11,11 +11,11 @@
autoware_cmake
autoware_ad_api_specs
+ autoware_component_interface_specs
autoware_control_msgs
autoware_external_api_msgs
autoware_system_msgs
autoware_vehicle_msgs
- component_interface_specs
component_interface_utils
nlohmann-json-dev
rclcpp
diff --git a/autoware_iv_external_api_adaptor/src/initial_pose.cpp b/autoware_iv_external_api_adaptor/src/initial_pose.cpp
index abf0ebe..3e769b3 100644
--- a/autoware_iv_external_api_adaptor/src/initial_pose.cpp
+++ b/autoware_iv_external_api_adaptor/src/initial_pose.cpp
@@ -60,8 +60,10 @@ void InitialPose::setInitializePose(
const tier4_external_api_msgs::srv::InitializePose::Request::SharedPtr request,
const tier4_external_api_msgs::srv::InitializePose::Response::SharedPtr response)
{
- const auto req = std::make_shared();
- req->method = localization_interface::Initialize::Service::Request::AUTO;
+ const auto req = std::make_shared<
+ autoware::component_interface_specs::localization::Initialize::Service::Request>();
+ req->method =
+ autoware::component_interface_specs::localization::Initialize::Service::Request::AUTO;
req->pose_with_covariance.push_back(request->pose);
req->pose_with_covariance.back().pose.covariance = particle_covariance;
@@ -77,8 +79,10 @@ void InitialPose::setInitializePoseAuto(
const tier4_external_api_msgs::srv::InitializePoseAuto::Request::SharedPtr,
const tier4_external_api_msgs::srv::InitializePoseAuto::Response::SharedPtr response)
{
- const auto req = std::make_shared();
- req->method = localization_interface::Initialize::Service::Request::AUTO;
+ const auto req = std::make_shared<
+ autoware::component_interface_specs::localization::Initialize::Service::Request>();
+ req->method =
+ autoware::component_interface_specs::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 535fbd9..c4bd49c 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
@@ -39,8 +39,8 @@ class InitialPose : public rclcpp::Node
rclcpp::CallbackGroup::SharedPtr group_;
tier4_api_utils::Service::SharedPtr srv_set_initialize_pose_;
tier4_api_utils::Service::SharedPtr srv_set_initialize_pose_auto_;
- component_interface_utils::Client::SharedPtr
- cli_localization_initialize_;
+ component_interface_utils::Client::
+ SharedPtr cli_localization_initialize_;
// ros callback
void setInitializePose(