@@ -509,6 +509,9 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
509
509
510
510
// State machine
511
511
if (mrm_state_.behavior == MrmState::NONE) {
512
+ if (is_operation_mode_availability_timeout) {
513
+ return MrmState::EMERGENCY_STOP;
514
+ }
512
515
if (operation_mode_availability_->pull_over ) {
513
516
if (param_.use_pull_over ) {
514
517
return MrmState::PULL_OVER;
@@ -525,6 +528,9 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
525
528
return MrmState::EMERGENCY_STOP;
526
529
}
527
530
if (mrm_state_.behavior == MrmState::PULL_OVER) {
531
+ if (is_operation_mode_availability_timeout) {
532
+ return MrmState::EMERGENCY_STOP;
533
+ }
528
534
if (operation_mode_availability_->pull_over ) {
529
535
if (param_.use_pull_over ) {
530
536
return MrmState::PULL_OVER;
@@ -541,6 +547,9 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
541
547
return MrmState::EMERGENCY_STOP;
542
548
}
543
549
if (mrm_state_.behavior == MrmState::COMFORTABLE_STOP) {
550
+ if (is_operation_mode_availability_timeout) {
551
+ return MrmState::EMERGENCY_STOP;
552
+ }
544
553
if (isStopped () && operation_mode_availability_->pull_over ) {
545
554
if (param_.use_pull_over ) {
546
555
return MrmState::PULL_OVER;
@@ -557,6 +566,9 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
557
566
return MrmState::EMERGENCY_STOP;
558
567
}
559
568
if (mrm_state_.behavior == MrmState::EMERGENCY_STOP) {
569
+ if (is_operation_mode_availability_timeout) {
570
+ return MrmState::EMERGENCY_STOP;
571
+ }
560
572
if (isStopped () && operation_mode_availability_->pull_over ) {
561
573
if (param_.use_pull_over ) {
562
574
return MrmState::PULL_OVER;
0 commit comments