@@ -91,6 +91,7 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
91
91
mrm_state_.stamp = this ->now ();
92
92
mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::NORMAL;
93
93
mrm_state_.behavior = autoware_adapi_v1_msgs::msg::MrmState::NONE;
94
+ is_operation_mode_availability_timeout = false ;
94
95
95
96
// Timer
96
97
const auto update_period_ns = rclcpp::Rate (param_.update_rate ).period ();
@@ -358,24 +359,29 @@ bool MrmHandler::isDataReady()
358
359
return true ;
359
360
}
360
361
361
- void MrmHandler::onTimer ()
362
+ void MrmHandler::checkOperationModeAvailabilityTimeout ()
362
363
{
363
- if (!isDataReady ()) {
364
- return ;
365
- }
366
- const bool is_operation_mode_availability_timeout =
364
+ if (
367
365
(this ->now () - stamp_operation_mode_availability_).seconds () >
368
- param_.timeout_operation_mode_availability ;
369
- if ( is_operation_mode_availability_timeout) {
366
+ param_.timeout_operation_mode_availability ) {
367
+ is_operation_mode_availability_timeout = true ;
370
368
RCLCPP_WARN_THROTTLE (
371
369
this ->get_logger (), *this ->get_clock (), std::chrono::milliseconds (1000 ).count (),
372
- " heartbeat operation_mode_availability is timeout" );
373
- mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::MRM_OPERATING;
374
- publishHazardCmd ();
375
- publishGearCmd ();
370
+ " operation_mode_availability is timeout" );
371
+ } else {
372
+ is_operation_mode_availability_timeout = false ;
373
+ }
374
+ }
375
+
376
+ void MrmHandler::onTimer ()
377
+ {
378
+ if (!isDataReady ()) {
376
379
return ;
377
380
}
378
381
382
+ // Check whether operation_mode_availability is timeout
383
+ checkOperationModeAvailabilityTimeout ();
384
+
379
385
// Update Emergency State
380
386
updateMrmState ();
381
387
@@ -477,6 +483,9 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
477
483
478
484
// State machine
479
485
if (mrm_state_.behavior == MrmState::NONE) {
486
+ if (is_operation_mode_availability_timeout) {
487
+ return MrmState::EMERGENCY_STOP;
488
+ }
480
489
if (operation_mode_availability_->pull_over ) {
481
490
if (param_.use_pull_over ) {
482
491
return MrmState::PULL_OVER;
@@ -493,6 +502,9 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
493
502
return MrmState::EMERGENCY_STOP;
494
503
}
495
504
if (mrm_state_.behavior == MrmState::PULL_OVER) {
505
+ if (is_operation_mode_availability_timeout) {
506
+ return MrmState::EMERGENCY_STOP;
507
+ }
496
508
if (operation_mode_availability_->pull_over ) {
497
509
if (param_.use_pull_over ) {
498
510
return MrmState::PULL_OVER;
@@ -509,6 +521,9 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
509
521
return MrmState::EMERGENCY_STOP;
510
522
}
511
523
if (mrm_state_.behavior == MrmState::COMFORTABLE_STOP) {
524
+ if (is_operation_mode_availability_timeout) {
525
+ return MrmState::EMERGENCY_STOP;
526
+ }
512
527
if (isStopped () && operation_mode_availability_->pull_over ) {
513
528
if (param_.use_pull_over ) {
514
529
return MrmState::PULL_OVER;
@@ -525,6 +540,9 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
525
540
return MrmState::EMERGENCY_STOP;
526
541
}
527
542
if (mrm_state_.behavior == MrmState::EMERGENCY_STOP) {
543
+ if (is_operation_mode_availability_timeout) {
544
+ return MrmState::EMERGENCY_STOP;
545
+ }
528
546
if (isStopped () && operation_mode_availability_->pull_over ) {
529
547
if (param_.use_pull_over ) {
530
548
return MrmState::PULL_OVER;
@@ -551,7 +569,8 @@ bool MrmHandler::isStopped()
551
569
552
570
bool MrmHandler::isEmergency () const
553
571
{
554
- return !operation_mode_availability_->autonomous || is_emergency_holding_;
572
+ return !operation_mode_availability_->autonomous || is_emergency_holding_ ||
573
+ is_operation_mode_availability_timeout;
555
574
}
556
575
557
576
bool MrmHandler::isArrivedAtGoal ()
0 commit comments