Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(autoware_iv_external_api_adaptor): update component_interface_utils dependency #127

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion autoware_iv_external_api_adaptor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,11 @@

<depend>autoware_ad_api_specs</depend>
<depend>autoware_component_interface_specs</depend>
<depend>autoware_component_interface_utils</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_external_api_msgs</depend>
<depend>autoware_system_msgs</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>component_interface_utils</depend>
<depend>nlohmann-json-dev</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
6 changes: 3 additions & 3 deletions autoware_iv_external_api_adaptor/src/initial_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ InitialPose::InitialPose(const rclcpp::NodeOptions & options)
std::bind(&InitialPose::setInitializePoseAuto, this, _1, _2), rmw_qos_profile_services_default,
group_);

const auto adaptor = component_interface_utils::NodeAdaptor(this);
const auto adaptor = autoware::component_interface_utils::NodeAdaptor(this);
adaptor.init_cli(cli_localization_initialize_);
}

Expand All @@ -70,7 +70,7 @@ void InitialPose::setInitializePose(
try {
const auto res = cli_localization_initialize_->call(req, initial_pose_timeout);
response->status = converter::convert(res->status);
} catch (const component_interface_utils::ServiceException & error) {
} catch (const autoware::component_interface_utils::ServiceException & error) {
response->status = tier4_api_utils::response_error(error.what());
}
}
Expand All @@ -87,7 +87,7 @@ void InitialPose::setInitializePoseAuto(
try {
const auto res = cli_localization_initialize_->call(req, initial_pose_timeout);
response->status = converter::convert(res->status);
} catch (const component_interface_utils::ServiceException & error) {
} catch (const autoware::component_interface_utils::ServiceException & error) {
response->status = tier4_api_utils::response_error(error.what());
}
}
Expand Down
7 changes: 4 additions & 3 deletions autoware_iv_external_api_adaptor/src/initial_pose.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#define INITIAL_POSE_HPP_

#include <autoware/component_interface_specs/localization.hpp>
#include <component_interface_utils/rclcpp.hpp>
#include <autoware/component_interface_utils/rclcpp.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_api_utils/tier4_api_utils.hpp>

Expand All @@ -39,8 +39,9 @@ class InitialPose : public rclcpp::Node
rclcpp::CallbackGroup::SharedPtr group_;
tier4_api_utils::Service<InitializePose>::SharedPtr srv_set_initialize_pose_;
tier4_api_utils::Service<InitializePoseAuto>::SharedPtr srv_set_initialize_pose_auto_;
component_interface_utils::Client<autoware::component_interface_specs::localization::Initialize>::
SharedPtr cli_localization_initialize_;
autoware::component_interface_utils::Client<
autoware::component_interface_specs::localization::Initialize>::SharedPtr
cli_localization_initialize_;

// ros callback
void setInitializePose(
Expand Down
6 changes: 3 additions & 3 deletions autoware_iv_external_api_adaptor/src/route.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ Route::Route(const rclcpp::NodeOptions & options) : Node("external_api_route", o

// adapi
{
const auto adaptor = component_interface_utils::NodeAdaptor(this);
const auto adaptor = autoware::component_interface_utils::NodeAdaptor(this);
adaptor.init_cli(cli_clear_route_);
adaptor.init_cli(cli_set_route_);
adaptor.init_sub(sub_get_route_, this, &Route::onRoute);
Expand All @@ -66,7 +66,7 @@ void Route::setRoute(
*req = converter::convert(*request);
const auto res = cli_set_route_->call(req);
response->status = converter::convert(res->status);
} catch (const component_interface_utils::ServiceException & error) {
} catch (const autoware::component_interface_utils::ServiceException & error) {
response->status = tier4_api_utils::response_error(error.what());
}
}
Expand All @@ -79,7 +79,7 @@ void Route::clearRoute(
const auto req = std::make_shared<autoware_ad_api::routing::ClearRoute::Service::Request>();
const auto res = cli_clear_route_->call(req);
response->status = converter::convert(res->status);
} catch (const component_interface_utils::ServiceException & error) {
} catch (const autoware::component_interface_utils::ServiceException & error) {
response->status = tier4_api_utils::response_error(error.what());
}
}
Expand Down
9 changes: 5 additions & 4 deletions autoware_iv_external_api_adaptor/src/route.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef ROUTE_HPP_
#define ROUTE_HPP_

#include "autoware/component_interface_utils/rclcpp.hpp"
#include "autoware_ad_api_specs/routing.hpp"
#include "component_interface_utils/rclcpp.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tier4_api_utils/tier4_api_utils.hpp"

Expand Down Expand Up @@ -44,10 +44,11 @@ class Route : public rclcpp::Node
tier4_api_utils::Service<SetRoute>::SharedPtr srv_set_route_;
tier4_api_utils::Service<ClearRoute>::SharedPtr srv_clear_route_;
rclcpp::Publisher<RouteMsg>::SharedPtr pub_get_route_;
component_interface_utils::Client<autoware_ad_api::routing::ClearRoute>::SharedPtr
autoware::component_interface_utils::Client<autoware_ad_api::routing::ClearRoute>::SharedPtr
cli_clear_route_;
component_interface_utils::Client<autoware_ad_api::routing::SetRoute>::SharedPtr cli_set_route_;
component_interface_utils::Subscription<autoware_ad_api::routing::Route>::SharedPtr
autoware::component_interface_utils::Client<autoware_ad_api::routing::SetRoute>::SharedPtr
cli_set_route_;
autoware::component_interface_utils::Subscription<autoware_ad_api::routing::Route>::SharedPtr
sub_get_route_;

// ros callback
Expand Down
Loading