Skip to content

Commit 3a883a8

Browse files
authored
Merge pull request #1582 from tier4/fix/concealer-7
Fix/concealer 7
2 parents 72dcb0a + de33adb commit 3a883a8

File tree

2 files changed

+52
-51
lines changed

2 files changed

+52
-51
lines changed

external/concealer/include/concealer/legacy_autoware_state.hpp

Lines changed: 50 additions & 49 deletions
Original file line numberDiff line numberDiff line change
@@ -88,55 +88,56 @@ struct LegacyAutowareState
8888
- https://github.com/autowarefoundation/autoware.universe/blob/e60daf7d1c85208eaac083b90c181e224c2ac513/system/autoware_default_adapi/document/autoware-state.md
8989
- https://github.com/autowarefoundation/autoware_universe/blob/e60daf7d1c85208eaac083b90c181e224c2ac513/system/autoware_default_adapi/src/compatibility/autoware_state.cpp#L80-L141
9090
*/
91-
switch (localization_state.state) {
92-
case autoware_adapi_v1_msgs::msg::LocalizationInitializationState::UNKNOWN:
93-
case autoware_adapi_v1_msgs::msg::LocalizationInitializationState::UNINITIALIZED:
94-
case autoware_adapi_v1_msgs::msg::LocalizationInitializationState::INITIALIZING:
95-
return initializing;
96-
97-
case autoware_adapi_v1_msgs::msg::LocalizationInitializationState::INITIALIZED:
98-
switch (route_state.state) {
99-
case autoware_adapi_v1_msgs::msg::RouteState::UNKNOWN:
100-
return initializing;
101-
102-
case autoware_adapi_v1_msgs::msg::RouteState::ARRIVED:
103-
if (const auto duration = now - rclcpp::Time(route_state.stamp);
104-
duration.seconds() < 2.0) {
105-
return arrived_goal;
106-
}
107-
[[fallthrough]];
108-
109-
case autoware_adapi_v1_msgs::msg::RouteState::UNSET:
110-
return waiting_for_route;
111-
112-
case autoware_adapi_v1_msgs::msg::RouteState::SET:
113-
case autoware_adapi_v1_msgs::msg::RouteState::CHANGING:
114-
switch (operation_mode_state.mode) {
115-
case autoware_adapi_v1_msgs::msg::OperationModeState::UNKNOWN:
116-
return initializing;
117-
118-
case autoware_adapi_v1_msgs::msg::OperationModeState::AUTONOMOUS:
119-
case autoware_adapi_v1_msgs::msg::OperationModeState::LOCAL:
120-
case autoware_adapi_v1_msgs::msg::OperationModeState::REMOTE:
121-
if (operation_mode_state.is_autoware_control_enabled) {
122-
return driving;
123-
}
124-
[[fallthrough]];
125-
126-
case autoware_adapi_v1_msgs::msg::OperationModeState::STOP:
127-
return operation_mode_state.is_autonomous_mode_available ? waiting_for_engage
128-
: planning;
129-
130-
default:
131-
return undefined;
132-
}
133-
134-
default:
135-
return undefined;
136-
}
137-
138-
default:
139-
return undefined;
91+
if (
92+
localization_state.state ==
93+
autoware_adapi_v1_msgs::msg::LocalizationInitializationState::UNKNOWN or
94+
route_state.state == autoware_adapi_v1_msgs::msg::RouteState::UNKNOWN or
95+
operation_mode_state.mode == autoware_adapi_v1_msgs::msg::OperationModeState::UNKNOWN) {
96+
return initializing;
97+
} else {
98+
switch (localization_state.state) {
99+
case autoware_adapi_v1_msgs::msg::LocalizationInitializationState::UNINITIALIZED:
100+
case autoware_adapi_v1_msgs::msg::LocalizationInitializationState::INITIALIZING:
101+
return initializing;
102+
103+
case autoware_adapi_v1_msgs::msg::LocalizationInitializationState::INITIALIZED:
104+
switch (route_state.state) {
105+
case autoware_adapi_v1_msgs::msg::RouteState::ARRIVED:
106+
if (const auto duration = now - rclcpp::Time(route_state.stamp);
107+
duration.seconds() < 2.0) {
108+
return arrived_goal;
109+
}
110+
[[fallthrough]];
111+
112+
case autoware_adapi_v1_msgs::msg::RouteState::UNSET:
113+
return waiting_for_route;
114+
115+
case autoware_adapi_v1_msgs::msg::RouteState::SET:
116+
case autoware_adapi_v1_msgs::msg::RouteState::CHANGING:
117+
switch (operation_mode_state.mode) {
118+
case autoware_adapi_v1_msgs::msg::OperationModeState::AUTONOMOUS:
119+
case autoware_adapi_v1_msgs::msg::OperationModeState::LOCAL:
120+
case autoware_adapi_v1_msgs::msg::OperationModeState::REMOTE:
121+
if (operation_mode_state.is_autoware_control_enabled) {
122+
return driving;
123+
}
124+
[[fallthrough]];
125+
126+
case autoware_adapi_v1_msgs::msg::OperationModeState::STOP:
127+
return operation_mode_state.is_autonomous_mode_available ? waiting_for_engage
128+
: planning;
129+
130+
default:
131+
return undefined;
132+
}
133+
134+
default:
135+
return undefined;
136+
}
137+
138+
default:
139+
return undefined;
140+
}
140141
}
141142
}())
142143
{

external/concealer/src/field_operator_application.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -145,11 +145,11 @@ FieldOperatorApplication::FieldOperatorApplication(const pid_t pid)
145145
minimum_risk_maneuver_behavior = behavior_name_of(message.behavior);
146146
}),
147147
#if __has_include(<autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>)
148-
getOperationModeState("/api/operation_mode/state", rclcpp::QoS(1), *this),
148+
getOperationModeState("/api/operation_mode/state", rclcpp::QoS(1).transient_local(), *this),
149149
#endif
150150
getPathWithLaneId("/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id", rclcpp::QoS(1), *this),
151151
#if __has_include(<autoware_adapi_v1_msgs/msg/route_state.hpp>)
152-
getRouteState("/api/routing/state", rclcpp::QoS(1), *this),
152+
getRouteState("/api/routing/state", rclcpp::QoS(1).transient_local(), *this),
153153
#endif
154154
getTurnIndicatorsCommand("/control/command/turn_indicators_cmd", rclcpp::QoS(1), *this),
155155
requestClearRoute("/api/routing/clear_route", *this),

0 commit comments

Comments
 (0)