@@ -29,6 +29,7 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
29
29
declare_parameter<double >(" timeout_cancel_mrm_behavior" , 0.01 );
30
30
param_.use_emergency_holding = declare_parameter<bool >(" use_emergency_holding" , false );
31
31
param_.timeout_emergency_recovery = declare_parameter<double >(" timeout_emergency_recovery" , 5.0 );
32
+ param_.is_mrm_recoverable = declare_parameter<bool >(" is_mrm_recoverable" , true );
32
33
param_.use_parking_after_stopped = declare_parameter<bool >(" use_parking_after_stopped" , false );
33
34
param_.use_pull_over = declare_parameter<bool >(" use_pull_over" , false );
34
35
param_.use_comfortable_stop = declare_parameter<bool >(" use_comfortable_stop" , false );
@@ -459,6 +460,8 @@ void MrmHandler::updateMrmState()
459
460
// NORMAL
460
461
if (is_vehicle_auto_mode && is_operation_mode_auto_mode && is_emergency) {
461
462
transitionTo (MrmState::MRM_OPERATING);
463
+ if (!param_.is_mrm_recoverable )
464
+ is_mrm_holding_ = true ;
462
465
return ;
463
466
}
464
467
} else {
@@ -590,7 +593,7 @@ bool MrmHandler::isStopped()
590
593
bool MrmHandler::isEmergency () const
591
594
{
592
595
return !operation_mode_availability_->autonomous || is_emergency_holding_ ||
593
- is_operation_mode_availability_timeout;
596
+ is_operation_mode_availability_timeout || is_mrm_holding_ ;
594
597
}
595
598
596
599
bool MrmHandler::isArrivedAtGoal ()
0 commit comments