Skip to content

Commit 1f769cd

Browse files
committed
fix: make universe suffix
Signed-off-by: Ryohsuke Mitsudome <ryohsuke.mitsudome@tier4.jp>
1 parent 5015ea3 commit 1f769cd

File tree

3 files changed

+7
-7
lines changed

3 files changed

+7
-7
lines changed

autoware_iv_external_api_adaptor/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@
1111
<buildtool_depend>autoware_cmake</buildtool_depend>
1212

1313
<depend>autoware_adapi_specs</depend>
14-
<depend>autoware_universe_component_interface_specs</depend>
14+
<depend>autoware_component_interface_specs_universe</depend>
1515
<depend>autoware_component_interface_utils</depend>
1616
<depend>autoware_control_msgs</depend>
1717
<depend>autoware_external_api_msgs</depend>

autoware_iv_external_api_adaptor/src/initial_pose.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -61,9 +61,9 @@ void InitialPose::setInitializePose(
6161
const tier4_external_api_msgs::srv::InitializePose::Response::SharedPtr response)
6262
{
6363
const auto req = std::make_shared<
64-
autoware::universe_component_interface_specs::localization::Initialize::Service::Request>();
64+
autoware::component_interface_specs_universe::localization::Initialize::Service::Request>();
6565
req->method =
66-
autoware::universe_component_interface_specs::localization::Initialize::Service::Request::AUTO;
66+
autoware::component_interface_specs_universe::localization::Initialize::Service::Request::AUTO;
6767
req->pose_with_covariance.push_back(request->pose);
6868
req->pose_with_covariance.back().pose.covariance = particle_covariance;
6969

@@ -80,9 +80,9 @@ void InitialPose::setInitializePoseAuto(
8080
const tier4_external_api_msgs::srv::InitializePoseAuto::Response::SharedPtr response)
8181
{
8282
const auto req = std::make_shared<
83-
autoware::universe_component_interface_specs::localization::Initialize::Service::Request>();
83+
autoware::component_interface_specs_universe::localization::Initialize::Service::Request>();
8484
req->method =
85-
autoware::universe_component_interface_specs::localization::Initialize::Service::Request::AUTO;
85+
autoware::component_interface_specs_universe::localization::Initialize::Service::Request::AUTO;
8686

8787
try {
8888
const auto res = cli_localization_initialize_->call(req, initial_pose_timeout);

autoware_iv_external_api_adaptor/src/initial_pose.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
#ifndef INITIAL_POSE_HPP_
1616
#define INITIAL_POSE_HPP_
1717

18-
#include <autoware/universe_component_interface_specs/localization.hpp>
18+
#include <autoware/component_interface_specs_universe/localization.hpp>
1919
#include <autoware/component_interface_utils/rclcpp.hpp>
2020
#include <rclcpp/rclcpp.hpp>
2121
#include <tier4_api_utils/tier4_api_utils.hpp>
@@ -40,7 +40,7 @@ class InitialPose : public rclcpp::Node
4040
tier4_api_utils::Service<InitializePose>::SharedPtr srv_set_initialize_pose_;
4141
tier4_api_utils::Service<InitializePoseAuto>::SharedPtr srv_set_initialize_pose_auto_;
4242
autoware::component_interface_utils::Client<
43-
autoware::universe_component_interface_specs::localization::Initialize>::SharedPtr
43+
autoware::component_interface_specs_universe::localization::Initialize>::SharedPtr
4444
cli_localization_initialize_;
4545

4646
// ros callback

0 commit comments

Comments
 (0)