Skip to content

Commit 9dc94c3

Browse files
committed
implement is_mrm_recoverable option of mrm_handler
1 parent 4b1f18e commit 9dc94c3

File tree

3 files changed

+7
-1
lines changed

3 files changed

+7
-1
lines changed

system/mrm_handler/config/mrm_handler.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
timeout_cancel_mrm_behavior: 0.01
99
use_emergency_holding: false
1010
timeout_emergency_recovery: 5.0
11+
is_mrm_recoverable: true
1112
use_parking_after_stopped: false
1213
use_pull_over: false
1314
use_comfortable_stop: false

system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,7 @@ struct Param
5151
double timeout_cancel_mrm_behavior;
5252
bool use_emergency_holding;
5353
double timeout_emergency_recovery;
54+
bool is_mrm_recoverable;
5455
bool use_parking_after_stopped;
5556
bool use_pull_over;
5657
bool use_comfortable_stop;
@@ -149,6 +150,7 @@ class MrmHandler : public rclcpp::Node
149150

150151
// Algorithm
151152
bool is_emergency_holding_ = false;
153+
bool is_mrm_holding_ = false;
152154
void transitionTo(const int new_state);
153155
void updateMrmState();
154156
void operateMrm();

system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
2929
declare_parameter<double>("timeout_cancel_mrm_behavior", 0.01);
3030
param_.use_emergency_holding = declare_parameter<bool>("use_emergency_holding", false);
3131
param_.timeout_emergency_recovery = declare_parameter<double>("timeout_emergency_recovery", 5.0);
32+
param_.is_mrm_recoverable = declare_parameter<bool>("is_mrm_recoverable", true);
3233
param_.use_parking_after_stopped = declare_parameter<bool>("use_parking_after_stopped", false);
3334
param_.use_pull_over = declare_parameter<bool>("use_pull_over", false);
3435
param_.use_comfortable_stop = declare_parameter<bool>("use_comfortable_stop", false);
@@ -459,6 +460,8 @@ void MrmHandler::updateMrmState()
459460
// NORMAL
460461
if (is_vehicle_auto_mode && is_operation_mode_auto_mode && is_emergency) {
461462
transitionTo(MrmState::MRM_OPERATING);
463+
if (!param_.is_mrm_recoverable)
464+
is_mrm_holding_ = true;
462465
return;
463466
}
464467
} else {
@@ -590,7 +593,7 @@ bool MrmHandler::isStopped()
590593
bool MrmHandler::isEmergency() const
591594
{
592595
return !operation_mode_availability_->autonomous || is_emergency_holding_ ||
593-
is_operation_mode_availability_timeout;
596+
is_operation_mode_availability_timeout || is_mrm_holding_;
594597
}
595598

596599
bool MrmHandler::isArrivedAtGoal()

0 commit comments

Comments
 (0)