From b6650a533a48dc5955e216307b6989a1046e9036 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Mon, 26 Aug 2024 15:05:12 +0900 Subject: [PATCH] fix(lane_change): update rtc status for some failure condition (#8604) update rtc status for some failure condition Signed-off-by: Go Sakayori --- .../src/interface.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 3f42eeb23f8f6..6db83e9011632 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -257,11 +257,17 @@ bool LaneChangeInterface::canTransitFailureState() if (!module_type_->isValidPath()) { log_debug_throttled("Transit to failure state due not to find valid path"); + updateRTCStatus( + std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, + State::FAILED); return true; } if (module_type_->isAbortState() && module_type_->hasFinishedAbort()) { log_debug_throttled("Abort process has completed."); + updateRTCStatus( + std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, + State::FAILED); return true; }