Skip to content

Commit d9ef8aa

Browse files
refactor(autoware_iv_external_api_adaptor): update component_interface_utils dependency (#127)
* refactor(autoware_iv_external_api_adaptor): update component_interface_utils dependency Signed-off-by: Esteve Fernandez <esteve@apache.org> * style(pre-commit): autofix --------- Signed-off-by: Esteve Fernandez <esteve@apache.org> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 3de19bc commit d9ef8aa

File tree

5 files changed

+16
-14
lines changed

5 files changed

+16
-14
lines changed

autoware_iv_external_api_adaptor/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,11 +12,11 @@
1212

1313
<depend>autoware_ad_api_specs</depend>
1414
<depend>autoware_component_interface_specs</depend>
15+
<depend>autoware_component_interface_utils</depend>
1516
<depend>autoware_control_msgs</depend>
1617
<depend>autoware_external_api_msgs</depend>
1718
<depend>autoware_system_msgs</depend>
1819
<depend>autoware_vehicle_msgs</depend>
19-
<depend>component_interface_utils</depend>
2020
<depend>nlohmann-json-dev</depend>
2121
<depend>rclcpp</depend>
2222
<depend>rclcpp_components</depend>

autoware_iv_external_api_adaptor/src/initial_pose.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ InitialPose::InitialPose(const rclcpp::NodeOptions & options)
5252
std::bind(&InitialPose::setInitializePoseAuto, this, _1, _2), rmw_qos_profile_services_default,
5353
group_);
5454

55-
const auto adaptor = component_interface_utils::NodeAdaptor(this);
55+
const auto adaptor = autoware::component_interface_utils::NodeAdaptor(this);
5656
adaptor.init_cli(cli_localization_initialize_);
5757
}
5858

@@ -70,7 +70,7 @@ void InitialPose::setInitializePose(
7070
try {
7171
const auto res = cli_localization_initialize_->call(req, initial_pose_timeout);
7272
response->status = converter::convert(res->status);
73-
} catch (const component_interface_utils::ServiceException & error) {
73+
} catch (const autoware::component_interface_utils::ServiceException & error) {
7474
response->status = tier4_api_utils::response_error(error.what());
7575
}
7676
}
@@ -87,7 +87,7 @@ void InitialPose::setInitializePoseAuto(
8787
try {
8888
const auto res = cli_localization_initialize_->call(req, initial_pose_timeout);
8989
response->status = converter::convert(res->status);
90-
} catch (const component_interface_utils::ServiceException & error) {
90+
} catch (const autoware::component_interface_utils::ServiceException & error) {
9191
response->status = tier4_api_utils::response_error(error.what());
9292
}
9393
}

autoware_iv_external_api_adaptor/src/initial_pose.hpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
1616
#define INITIAL_POSE_HPP_
1717

1818
#include <autoware/component_interface_specs/localization.hpp>
19-
#include <component_interface_utils/rclcpp.hpp>
19+
#include <autoware/component_interface_utils/rclcpp.hpp>
2020
#include <rclcpp/rclcpp.hpp>
2121
#include <tier4_api_utils/tier4_api_utils.hpp>
2222

@@ -39,8 +39,9 @@ class InitialPose : public rclcpp::Node
3939
rclcpp::CallbackGroup::SharedPtr group_;
4040
tier4_api_utils::Service<InitializePose>::SharedPtr srv_set_initialize_pose_;
4141
tier4_api_utils::Service<InitializePoseAuto>::SharedPtr srv_set_initialize_pose_auto_;
42-
component_interface_utils::Client<autoware::component_interface_specs::localization::Initialize>::
43-
SharedPtr cli_localization_initialize_;
42+
autoware::component_interface_utils::Client<
43+
autoware::component_interface_specs::localization::Initialize>::SharedPtr
44+
cli_localization_initialize_;
4445

4546
// ros callback
4647
void setInitializePose(

autoware_iv_external_api_adaptor/src/route.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ Route::Route(const rclcpp::NodeOptions & options) : Node("external_api_route", o
4343

4444
// adapi
4545
{
46-
const auto adaptor = component_interface_utils::NodeAdaptor(this);
46+
const auto adaptor = autoware::component_interface_utils::NodeAdaptor(this);
4747
adaptor.init_cli(cli_clear_route_);
4848
adaptor.init_cli(cli_set_route_);
4949
adaptor.init_sub(sub_get_route_, this, &Route::onRoute);
@@ -66,7 +66,7 @@ void Route::setRoute(
6666
*req = converter::convert(*request);
6767
const auto res = cli_set_route_->call(req);
6868
response->status = converter::convert(res->status);
69-
} catch (const component_interface_utils::ServiceException & error) {
69+
} catch (const autoware::component_interface_utils::ServiceException & error) {
7070
response->status = tier4_api_utils::response_error(error.what());
7171
}
7272
}
@@ -79,7 +79,7 @@ void Route::clearRoute(
7979
const auto req = std::make_shared<autoware_ad_api::routing::ClearRoute::Service::Request>();
8080
const auto res = cli_clear_route_->call(req);
8181
response->status = converter::convert(res->status);
82-
} catch (const component_interface_utils::ServiceException & error) {
82+
} catch (const autoware::component_interface_utils::ServiceException & error) {
8383
response->status = tier4_api_utils::response_error(error.what());
8484
}
8585
}

autoware_iv_external_api_adaptor/src/route.hpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,8 @@
1515
#ifndef ROUTE_HPP_
1616
#define ROUTE_HPP_
1717

18+
#include "autoware/component_interface_utils/rclcpp.hpp"
1819
#include "autoware_ad_api_specs/routing.hpp"
19-
#include "component_interface_utils/rclcpp.hpp"
2020
#include "rclcpp/rclcpp.hpp"
2121
#include "tier4_api_utils/tier4_api_utils.hpp"
2222

@@ -44,10 +44,11 @@ class Route : public rclcpp::Node
4444
tier4_api_utils::Service<SetRoute>::SharedPtr srv_set_route_;
4545
tier4_api_utils::Service<ClearRoute>::SharedPtr srv_clear_route_;
4646
rclcpp::Publisher<RouteMsg>::SharedPtr pub_get_route_;
47-
component_interface_utils::Client<autoware_ad_api::routing::ClearRoute>::SharedPtr
47+
autoware::component_interface_utils::Client<autoware_ad_api::routing::ClearRoute>::SharedPtr
4848
cli_clear_route_;
49-
component_interface_utils::Client<autoware_ad_api::routing::SetRoute>::SharedPtr cli_set_route_;
50-
component_interface_utils::Subscription<autoware_ad_api::routing::Route>::SharedPtr
49+
autoware::component_interface_utils::Client<autoware_ad_api::routing::SetRoute>::SharedPtr
50+
cli_set_route_;
51+
autoware::component_interface_utils::Subscription<autoware_ad_api::routing::Route>::SharedPtr
5152
sub_get_route_;
5253

5354
// ros callback

0 commit comments

Comments
 (0)