@@ -32,6 +32,7 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
32
32
param_.is_mrm_recoverable = declare_parameter<bool >(" is_mrm_recoverable" , true );
33
33
param_.use_parking_after_stopped = declare_parameter<bool >(" use_parking_after_stopped" , false );
34
34
param_.use_pull_over = declare_parameter<bool >(" use_pull_over" , false );
35
+ param_.use_pull_over_after_stopped = declare_parameter<bool >(" use_pull_over_after_stopped" , false );
35
36
param_.use_comfortable_stop = declare_parameter<bool >(" use_comfortable_stop" , false );
36
37
param_.turning_hazard_on .emergency = declare_parameter<bool >(" turning_hazard_on.emergency" , true );
37
38
@@ -548,7 +549,7 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
548
549
return MrmState::EMERGENCY_STOP;
549
550
}
550
551
if (isStopped () && operation_mode_availability_->pull_over ) {
551
- if (param_.use_pull_over ) {
552
+ if (param_.use_pull_over && param_. use_pull_over_after_stopped ) {
552
553
return MrmState::PULL_OVER;
553
554
}
554
555
}
@@ -567,7 +568,7 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
567
568
return MrmState::EMERGENCY_STOP;
568
569
}
569
570
if (isStopped () && operation_mode_availability_->pull_over ) {
570
- if (param_.use_pull_over ) {
571
+ if (param_.use_pull_over && param_. use_pull_over_after_stopped ) {
571
572
return MrmState::PULL_OVER;
572
573
}
573
574
}
0 commit comments