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

fix(external): fix old package name #128

Merged
merged 4 commits into from
Nov 12, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
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 @@ -10,7 +10,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_ad_api_specs</depend>
<depend>autoware_adapi_spec</depend>
<depend>autoware_component_interface_specs</depend>
<depend>autoware_component_interface_utils</depend>
<depend>autoware_control_msgs</depend>
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 @@ -62,7 +62,7 @@ void Route::setRoute(
}

try {
const auto req = std::make_shared<autoware_ad_api::routing::SetRoute::Service::Request>();
const auto req = std::make_shared<autoware_adapi::routing::SetRoute::Service::Request>();
*req = converter::convert(*request);
const auto res = cli_set_route_->call(req);
response->status = converter::convert(res->status);
Expand All @@ -76,15 +76,15 @@ void Route::clearRoute(
const tier4_external_api_msgs::srv::ClearRoute::Response::SharedPtr response)
{
try {
const auto req = std::make_shared<autoware_ad_api::routing::ClearRoute::Service::Request>();
const auto req = std::make_shared<autoware_adapi::routing::ClearRoute::Service::Request>();
const auto res = cli_clear_route_->call(req);
response->status = converter::convert(res->status);
} catch (const autoware::component_interface_utils::ServiceException & error) {
response->status = tier4_api_utils::response_error(error.what());
}
}

void Route::onRoute(const autoware_ad_api::routing::Route::Message::ConstSharedPtr message)
void Route::onRoute(const autoware_adapi::routing::Route::Message::ConstSharedPtr message)
{
if (!message->data.empty()) {
pub_get_route_->publish(converter::convert(*message));
Expand Down
10 changes: 5 additions & 5 deletions autoware_iv_external_api_adaptor/src/route.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#define ROUTE_HPP_

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

Expand Down Expand Up @@ -44,11 +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_;
autoware::component_interface_utils::Client<autoware_ad_api::routing::ClearRoute>::SharedPtr
autoware::component_interface_utils::Client<autoware_adapi::routing::ClearRoute>::SharedPtr
cli_clear_route_;
autoware::component_interface_utils::Client<autoware_ad_api::routing::SetRoute>::SharedPtr
autoware::component_interface_utils::Client<autoware_adapi::routing::SetRoute>::SharedPtr
cli_set_route_;
autoware::component_interface_utils::Subscription<autoware_ad_api::routing::Route>::SharedPtr
autoware::component_interface_utils::Subscription<autoware_adapi::routing::Route>::SharedPtr
sub_get_route_;

// ros callback
Expand All @@ -58,7 +58,7 @@ class Route : public rclcpp::Node
void clearRoute(
const tier4_external_api_msgs::srv::ClearRoute::Request::SharedPtr request,
const tier4_external_api_msgs::srv::ClearRoute::Response::SharedPtr response);
void onRoute(const autoware_ad_api::routing::Route::Message::ConstSharedPtr message);
void onRoute(const autoware_adapi::routing::Route::Message::ConstSharedPtr message);
};

} // namespace external_api
Expand Down
Loading