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

feat(mrm_handler): operate mrm only when autonomous operation mode #1377

Merged
merged 1 commit into from
Jul 3, 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 @@ -148,7 +148,8 @@ class MrmHandler : public rclcpp::Node
bool isStopped();
bool isDrivingBackwards();
bool isEmergency() const;
bool isAutonomous();
bool isControlModeAutonomous();
bool isOperationModeAutonomous();
bool isPullOverStatusAvailable();
bool isComfortableStopStatusAvailable();
bool isEmergencyStopStatusAvailable();
Expand Down
15 changes: 12 additions & 3 deletions system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -396,12 +396,13 @@ void MrmHandler::updateMrmState()
}

// Get mode
const bool is_auto_mode = isAutonomous();
const bool is_control_mode_autonomous = isControlModeAutonomous();
const bool is_operation_mode_autonomous = isOperationModeAutonomous();

// State Machine
switch (mrm_state_.state) {
case MrmState::NORMAL:
if (is_auto_mode) {
if (is_control_mode_autonomous && is_operation_mode_autonomous) {
transitionTo(MrmState::MRM_OPERATING);
}
return;
Expand Down Expand Up @@ -537,14 +538,22 @@ bool MrmHandler::isEmergency() const
is_operation_mode_availability_timeout;
}

bool MrmHandler::isAutonomous()
bool MrmHandler::isControlModeAutonomous()
{
using autoware_vehicle_msgs::msg::ControlModeReport;
auto mode = sub_control_mode_.takeData();
if (mode == nullptr) return false;
return mode->mode == ControlModeReport::AUTONOMOUS;
}

bool MrmHandler::isOperationModeAutonomous()
{
using autoware_adapi_v1_msgs::msg::OperationModeState;
auto state = sub_operation_mode_state_.takeData();
if (state == nullptr) return false;
return state->mode == OperationModeState::AUTONOMOUS;
}

bool MrmHandler::isPullOverStatusAvailable()
{
auto status = sub_mrm_pull_over_status_.takeData();
Expand Down
Loading