File tree 2 files changed +9
-8
lines changed
autoware_iv_external_api_adaptor/src
2 files changed +9
-8
lines changed Original file line number Diff line number Diff line change @@ -62,7 +62,7 @@ void Route::setRoute(
62
62
}
63
63
64
64
try {
65
- const auto req = std::make_shared<autoware_adapi ::routing::SetRoute::Service::Request>();
65
+ const auto req = std::make_shared<autoware::adapi_specs ::routing::SetRoute::Service::Request>();
66
66
*req = converter::convert (*request);
67
67
const auto res = cli_set_route_->call (req);
68
68
response->status = converter::convert (res->status );
@@ -76,15 +76,16 @@ void Route::clearRoute(
76
76
const tier4_external_api_msgs::srv::ClearRoute::Response::SharedPtr response)
77
77
{
78
78
try {
79
- const auto req = std::make_shared<autoware_adapi::routing::ClearRoute::Service::Request>();
79
+ const auto req =
80
+ std::make_shared<autoware::adapi_specs::routing::ClearRoute::Service::Request>();
80
81
const auto res = cli_clear_route_->call (req);
81
82
response->status = converter::convert (res->status );
82
83
} catch (const autoware::component_interface_utils::ServiceException & error) {
83
84
response->status = tier4_api_utils::response_error (error.what ());
84
85
}
85
86
}
86
87
87
- void Route::onRoute (const autoware_adapi ::routing::Route::Message::ConstSharedPtr message)
88
+ void Route::onRoute (const autoware::adapi_specs ::routing::Route::Message::ConstSharedPtr message)
88
89
{
89
90
if (!message->data .empty ()) {
90
91
pub_get_route_->publish (converter::convert (*message));
Original file line number Diff line number Diff line change @@ -44,12 +44,12 @@ class Route : public rclcpp::Node
44
44
tier4_api_utils::Service<SetRoute>::SharedPtr srv_set_route_;
45
45
tier4_api_utils::Service<ClearRoute>::SharedPtr srv_clear_route_;
46
46
rclcpp::Publisher<RouteMsg>::SharedPtr pub_get_route_;
47
- autoware::component_interface_utils::Client<autoware_adapi ::routing::ClearRoute>::SharedPtr
47
+ autoware::component_interface_utils::Client<autoware::adapi_specs ::routing::ClearRoute>::SharedPtr
48
48
cli_clear_route_;
49
- autoware::component_interface_utils::Client<autoware_adapi ::routing::SetRoute>::SharedPtr
49
+ autoware::component_interface_utils::Client<autoware::adapi_specs ::routing::SetRoute>::SharedPtr
50
50
cli_set_route_;
51
- autoware::component_interface_utils::Subscription<autoware_adapi::routing::Route>::SharedPtr
52
- sub_get_route_;
51
+ autoware::component_interface_utils::Subscription<
52
+ autoware::adapi_specs::routing::Route>::SharedPtr sub_get_route_;
53
53
54
54
// ros callback
55
55
void setRoute (
@@ -58,7 +58,7 @@ class Route : public rclcpp::Node
58
58
void clearRoute (
59
59
const tier4_external_api_msgs::srv::ClearRoute::Request::SharedPtr request,
60
60
const tier4_external_api_msgs::srv::ClearRoute::Response::SharedPtr response);
61
- void onRoute (const autoware_adapi ::routing::Route::Message::ConstSharedPtr message);
61
+ void onRoute (const autoware::adapi_specs ::routing::Route::Message::ConstSharedPtr message);
62
62
};
63
63
64
64
} // namespace external_api
You can’t perform that action at this time.
0 commit comments