Skip to content

Commit f0406a4

Browse files
committed
RJD-1666 Change PathWithLaneId subscription to /api/routing/route
1 parent 5d1781f commit f0406a4

File tree

3 files changed

+8
-6
lines changed

3 files changed

+8
-6
lines changed

external/concealer/include/concealer/field_operator_application.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include <sys/wait.h>
1919

2020
#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
21+
#include <autoware_adapi_v1_msgs/msg/route.hpp>
2122
#include <autoware_adapi_v1_msgs/srv/change_operation_mode.hpp>
2223
#include <autoware_adapi_v1_msgs/srv/clear_route.hpp>
2324
#include <autoware_adapi_v1_msgs/srv/initialize_localization.hpp>
@@ -89,6 +90,7 @@ struct FieldOperatorApplication : public rclcpp::Node
8990
using AutoModeWithModule = tier4_rtc_msgs::srv::AutoModeWithModule;
9091
using SetVelocityLimit = tier4_external_api_msgs::srv::SetVelocityLimit;
9192
using ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode;
93+
using Route = autoware_adapi_v1_msgs::msg::Route;
9294

9395
Subscriber<AutowareState> getAutowareState;
9496
Subscriber<Control> getCommand;
@@ -101,7 +103,7 @@ struct FieldOperatorApplication : public rclcpp::Node
101103
#if __has_include(<autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>)
102104
Subscriber<OperationModeState> getOperationModeState;
103105
#endif
104-
Subscriber<priority::PathWithLaneId> getPathWithLaneId;
106+
Subscriber<Route> getRoute;
105107
#if __has_include(<autoware_adapi_v1_msgs/msg/route_state.hpp>)
106108
Subscriber<RouteState> getRouteState;
107109
#endif

external/concealer/src/field_operator_application.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -147,7 +147,7 @@ FieldOperatorApplication::FieldOperatorApplication(const pid_t pid)
147147
#if __has_include(<autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>)
148148
getOperationModeState("/api/operation_mode/state", rclcpp::QoS(1).transient_local(), *this),
149149
#endif
150-
getPathWithLaneId("/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id", rclcpp::QoS(1), *this),
150+
getRoute("/api/routing/route", rclcpp::QoS(1), *this),
151151
#if __has_include(<autoware_adapi_v1_msgs/msg/route_state.hpp>)
152152
getRouteState("/api/routing/state", rclcpp::QoS(1).transient_local(), *this),
153153
#endif

simulation/traffic_simulator/src/entity/ego_entity.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -143,11 +143,11 @@ auto EgoEntity::getObstacle() -> std::optional<traffic_simulator_msgs::msg::Obst
143143
auto EgoEntity::getRouteLanelets(double /*unused horizon*/) -> lanelet::Ids
144144
{
145145
lanelet::Ids ids{};
146-
147-
for (const auto & point : getPathWithLaneId().points) {
148-
ids += point.lane_ids;
146+
for (const auto & route_data : getRoute().data) {
147+
for (const auto & segment : route_data.segments) {
148+
ids.push_back(segment.preferred.id);
149+
}
149150
}
150-
151151
return ids;
152152
}
153153

0 commit comments

Comments
 (0)