Skip to content

Commit 7d69e00

Browse files
refactor(mrm_handler): use switch for state machine (#7277)
* refactor nested if elses Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * delete other commits Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * return for consistency Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> --------- Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent ff2fbd6 commit 7d69e00

File tree

1 file changed

+29
-29
lines changed

1 file changed

+29
-29
lines changed

system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp

+29-29
Original file line numberDiff line numberDiff line change
@@ -453,48 +453,48 @@ void MrmHandler::updateMrmState()
453453
// Check emergency
454454
const bool is_emergency = isEmergency();
455455

456+
// Send recovery events if is not an emergency
457+
if (!is_emergency) {
458+
if (mrm_state_.state != MrmState::NORMAL) transitionTo(MrmState::NORMAL);
459+
return;
460+
}
461+
456462
// Get mode
457463
const bool is_auto_mode = control_mode_->mode == ControlModeReport::AUTONOMOUS;
458464

459465
// State Machine
460-
if (mrm_state_.state == MrmState::NORMAL) {
461-
// NORMAL
462-
if (is_auto_mode && is_emergency) {
463-
transitionTo(MrmState::MRM_OPERATING);
464-
return;
465-
}
466-
} else {
467-
// Emergency
468-
// Send recovery events if "not emergency"
469-
if (!is_emergency) {
470-
transitionTo(MrmState::NORMAL);
466+
switch (mrm_state_.state) {
467+
case MrmState::NORMAL:
468+
if (is_auto_mode) {
469+
transitionTo(MrmState::MRM_OPERATING);
470+
}
471471
return;
472-
}
473472

474-
if (mrm_state_.state == MrmState::MRM_OPERATING) {
475-
// TODO(TetsuKawa): Check MRC is accomplished
476-
if (mrm_state_.behavior == MrmState::PULL_OVER) {
477-
if (isStopped() && isArrivedAtGoal()) {
478-
transitionTo(MrmState::MRM_SUCCEEDED);
479-
return;
480-
}
481-
} else {
482-
if (isStopped()) {
483-
transitionTo(MrmState::MRM_SUCCEEDED);
484-
return;
485-
}
473+
case MrmState::MRM_OPERATING:
474+
if (!isStopped()) return;
475+
if (mrm_state_.behavior != MrmState::PULL_OVER) {
476+
transitionTo(MrmState::MRM_SUCCEEDED);
477+
return;
478+
}
479+
if (isArrivedAtGoal()) {
480+
transitionTo(MrmState::MRM_SUCCEEDED);
486481
}
487-
} else if (mrm_state_.state == MrmState::MRM_SUCCEEDED) {
488-
const auto current_mrm_behavior = getCurrentMrmBehavior();
489-
if (current_mrm_behavior != mrm_state_.behavior) {
482+
return;
483+
484+
case MrmState::MRM_SUCCEEDED:
485+
if (mrm_state_.behavior != getCurrentMrmBehavior()) {
490486
transitionTo(MrmState::MRM_OPERATING);
491487
}
492-
} else if (mrm_state_.state == MrmState::MRM_FAILED) {
488+
return;
489+
case MrmState::MRM_FAILED:
493490
// Do nothing(only checking common recovery events)
494-
} else {
491+
return;
492+
493+
default: {
495494
const auto msg = "invalid state: " + std::to_string(mrm_state_.state);
496495
throw std::runtime_error(msg);
497496
}
497+
return;
498498
}
499499
}
500500

0 commit comments

Comments
 (0)