Skip to content
Open
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
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <sys/wait.h>

#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
#include <autoware_adapi_v1_msgs/msg/route.hpp>
#include <autoware_adapi_v1_msgs/srv/change_operation_mode.hpp>
#include <autoware_adapi_v1_msgs/srv/clear_route.hpp>
#include <autoware_adapi_v1_msgs/srv/initialize_localization.hpp>
Expand Down Expand Up @@ -89,6 +90,7 @@ struct FieldOperatorApplication : public rclcpp::Node
using AutoModeWithModule = tier4_rtc_msgs::srv::AutoModeWithModule;
using SetVelocityLimit = tier4_external_api_msgs::srv::SetVelocityLimit;
using ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode;
using Route = autoware_adapi_v1_msgs::msg::Route;

Subscriber<AutowareState> getAutowareState;
Subscriber<Control> getCommand;
Expand All @@ -101,7 +103,7 @@ struct FieldOperatorApplication : public rclcpp::Node
#if __has_include(<autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>)
Subscriber<OperationModeState> getOperationModeState;
#endif
Subscriber<priority::PathWithLaneId> getPathWithLaneId;
Subscriber<Route> getRoute;
#if __has_include(<autoware_adapi_v1_msgs/msg/route_state.hpp>)
Subscriber<RouteState> getRouteState;
#endif
Expand Down
2 changes: 1 addition & 1 deletion external/concealer/src/field_operator_application.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ FieldOperatorApplication::FieldOperatorApplication(const pid_t pid)
#if __has_include(<autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>)
getOperationModeState("/api/operation_mode/state", rclcpp::QoS(1).transient_local(), *this),
#endif
getPathWithLaneId("/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id", rclcpp::QoS(1), *this),
getRoute("/api/routing/route", rclcpp::QoS(1), *this),
#if __has_include(<autoware_adapi_v1_msgs/msg/route_state.hpp>)
getRouteState("/api/routing/state", rclcpp::QoS(1).transient_local(), *this),
#endif
Expand Down
8 changes: 4 additions & 4 deletions simulation/traffic_simulator/src/entity/ego_entity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,11 +143,11 @@ auto EgoEntity::getObstacle() -> std::optional<traffic_simulator_msgs::msg::Obst
auto EgoEntity::getRouteLanelets(double /*unused horizon*/) -> lanelet::Ids
{
lanelet::Ids ids{};

for (const auto & point : getPathWithLaneId().points) {
ids += point.lane_ids;
for (const auto & route_data : getRoute().data) {
for (const auto & segment : route_data.segments) {
ids.push_back(segment.preferred.id);
}
}

return ids;
}

Expand Down