Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(emergency_handler): fix hazard status timeout #6399

Merged
merged 3 commits into from
Mar 8, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -131,14 +131,16 @@ class EmergencyHandler : public rclcpp::Node

// Heartbeat
rclcpp::Time stamp_hazard_status_;
bool is_hazard_status_timeout_;
void checkHazardStatusTimeout();

// Algorithm
void transitionTo(const int new_state);
void updateMrmState();
void operateMrm();
autoware_adapi_v1_msgs::msg::MrmState::_behavior_type getCurrentMrmBehavior();
bool isStopped();
bool isEmergency(const autoware_auto_system_msgs::msg::HazardStatus & hazard_status);
bool isEmergency();
};

#endif // EMERGENCY_HANDLER__EMERGENCY_HANDLER_CORE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,7 @@
mrm_state_.stamp = this->now();
mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::NORMAL;
mrm_state_.behavior = autoware_adapi_v1_msgs::msg::MrmState::NONE;
is_hazard_status_timeout_ = false;

Check warning on line 86 in system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp#L86

Added line #L86 was not covered by tests

// Timer
const auto update_period_ns = rclcpp::Rate(param_.update_rate).period();
Expand Down Expand Up @@ -135,7 +136,7 @@
HazardLightsCommand msg;

// Check emergency
const bool is_emergency = isEmergency(hazard_status_stamped_->status);
const bool is_emergency = isEmergency();

if (hazard_status_stamped_->status.emergency_holding) {
// turn hazard on during emergency holding
Expand Down Expand Up @@ -309,22 +310,27 @@
return true;
}

void EmergencyHandler::onTimer()
void EmergencyHandler::checkHazardStatusTimeout()

Check warning on line 313 in system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp#L313

Added line #L313 was not covered by tests
{
if (!isDataReady()) {
return;
}
const bool is_hazard_status_timeout =
(this->now() - stamp_hazard_status_).seconds() > param_.timeout_hazard_status;
if (is_hazard_status_timeout) {
if ((this->now() - stamp_hazard_status_).seconds() > param_.timeout_hazard_status) {
is_hazard_status_timeout_ = true;

Check warning on line 316 in system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp#L315-L316

Added lines #L315 - L316 were not covered by tests
RCLCPP_WARN_THROTTLE(
this->get_logger(), *this->get_clock(), std::chrono::milliseconds(1000).count(),
"heartbeat_hazard_status is timeout");
mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::MRM_OPERATING;
publishControlCommands();
} else {
is_hazard_status_timeout_ = false;

Check warning on line 321 in system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp#L321

Added line #L321 was not covered by tests
}
}

Check warning on line 323 in system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp#L323

Added line #L323 was not covered by tests

void EmergencyHandler::onTimer()

Check warning on line 325 in system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp#L325

Added line #L325 was not covered by tests
{
if (!isDataReady()) {

Check warning on line 327 in system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp#L327

Added line #L327 was not covered by tests
return;
}

// Check whether heartbeat hazard_status is timeout
checkHazardStatusTimeout();

Check warning on line 332 in system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp#L332

Added line #L332 was not covered by tests

// Update Emergency State
updateMrmState();

Expand Down Expand Up @@ -369,7 +375,7 @@
using autoware_auto_vehicle_msgs::msg::ControlModeReport;

// Check emergency
const bool is_emergency = isEmergency(hazard_status_stamped_->status);
const bool is_emergency = isEmergency();

// Get mode
const bool is_auto_mode = control_mode_->mode == ControlModeReport::AUTONOMOUS;
Expand Down Expand Up @@ -412,7 +418,10 @@
using autoware_auto_system_msgs::msg::HazardStatus;

// Get hazard level
const auto level = hazard_status_stamped_->status.level;
auto level = hazard_status_stamped_->status.level;
if (is_hazard_status_timeout_) {

Check warning on line 422 in system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp#L421-L422

Added lines #L421 - L422 were not covered by tests
level = HazardStatus::SINGLE_POINT_FAULT;
}

// State machine
if (mrm_state_.behavior == MrmState::NONE) {
Expand All @@ -435,10 +444,10 @@
return mrm_state_.behavior;
}

bool EmergencyHandler::isEmergency(
const autoware_auto_system_msgs::msg::HazardStatus & hazard_status)
bool EmergencyHandler::isEmergency()

Check warning on line 447 in system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp#L447

Added line #L447 was not covered by tests
{
return hazard_status.emergency || hazard_status.emergency_holding;
return hazard_status_stamped_->status.emergency ||
hazard_status_stamped_->status.emergency_holding || is_hazard_status_timeout_;

Check warning on line 450 in system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp#L449-L450

Added lines #L449 - L450 were not covered by tests
}

bool EmergencyHandler::isStopped()
Expand Down
Loading