Skip to content

Commit 25ac89b

Browse files
veqccmkuri
authored andcommitted
fix(mrm_handler): fix bug in operation mode availability timeout (autowarefoundation#6513)
* fix operation mode availability timeout Signed-off-by: veqcc <ryuta.kambe@tier4.jp>
1 parent f99efa3 commit 25ac89b

File tree

2 files changed

+33
-12
lines changed

2 files changed

+33
-12
lines changed

system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -140,6 +140,8 @@ class MrmHandler : public rclcpp::Node
140140
// Heartbeat
141141
rclcpp::Time stamp_operation_mode_availability_;
142142
std::optional<rclcpp::Time> stamp_autonomous_become_unavailable_ = std::nullopt;
143+
bool is_operation_mode_availability_timeout;
144+
void checkOperationModeAvailabilityTimeout();
143145

144146
// Algorithm
145147
bool is_emergency_holding_ = false;

system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp

+31-12
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,7 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
9191
mrm_state_.stamp = this->now();
9292
mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::NORMAL;
9393
mrm_state_.behavior = autoware_adapi_v1_msgs::msg::MrmState::NONE;
94+
is_operation_mode_availability_timeout = false;
9495

9596
// Timer
9697
const auto update_period_ns = rclcpp::Rate(param_.update_rate).period();
@@ -358,24 +359,29 @@ bool MrmHandler::isDataReady()
358359
return true;
359360
}
360361

361-
void MrmHandler::onTimer()
362+
void MrmHandler::checkOperationModeAvailabilityTimeout()
362363
{
363-
if (!isDataReady()) {
364-
return;
365-
}
366-
const bool is_operation_mode_availability_timeout =
364+
if (
367365
(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;
370368
RCLCPP_WARN_THROTTLE(
371369
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()) {
376379
return;
377380
}
378381

382+
// Check whether operation_mode_availability is timeout
383+
checkOperationModeAvailabilityTimeout();
384+
379385
// Update Emergency State
380386
updateMrmState();
381387

@@ -477,6 +483,9 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
477483

478484
// State machine
479485
if (mrm_state_.behavior == MrmState::NONE) {
486+
if (is_operation_mode_availability_timeout) {
487+
return MrmState::EMERGENCY_STOP;
488+
}
480489
if (operation_mode_availability_->pull_over) {
481490
if (param_.use_pull_over) {
482491
return MrmState::PULL_OVER;
@@ -493,6 +502,9 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
493502
return MrmState::EMERGENCY_STOP;
494503
}
495504
if (mrm_state_.behavior == MrmState::PULL_OVER) {
505+
if (is_operation_mode_availability_timeout) {
506+
return MrmState::EMERGENCY_STOP;
507+
}
496508
if (operation_mode_availability_->pull_over) {
497509
if (param_.use_pull_over) {
498510
return MrmState::PULL_OVER;
@@ -509,6 +521,9 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
509521
return MrmState::EMERGENCY_STOP;
510522
}
511523
if (mrm_state_.behavior == MrmState::COMFORTABLE_STOP) {
524+
if (is_operation_mode_availability_timeout) {
525+
return MrmState::EMERGENCY_STOP;
526+
}
512527
if (isStopped() && operation_mode_availability_->pull_over) {
513528
if (param_.use_pull_over) {
514529
return MrmState::PULL_OVER;
@@ -525,6 +540,9 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB
525540
return MrmState::EMERGENCY_STOP;
526541
}
527542
if (mrm_state_.behavior == MrmState::EMERGENCY_STOP) {
543+
if (is_operation_mode_availability_timeout) {
544+
return MrmState::EMERGENCY_STOP;
545+
}
528546
if (isStopped() && operation_mode_availability_->pull_over) {
529547
if (param_.use_pull_over) {
530548
return MrmState::PULL_OVER;
@@ -551,7 +569,8 @@ bool MrmHandler::isStopped()
551569

552570
bool MrmHandler::isEmergency() const
553571
{
554-
return !operation_mode_availability_->autonomous || is_emergency_holding_;
572+
return !operation_mode_availability_->autonomous || is_emergency_holding_ ||
573+
is_operation_mode_availability_timeout;
555574
}
556575

557576
bool MrmHandler::isArrivedAtGoal()

0 commit comments

Comments
 (0)