From a6c0b5c447575c335cb956fc0540d9d4bb9a90d7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 25 Apr 2015 12:42:04 +0200 Subject: commander: Improve state feedback after preflight check resolution --- src/modules/commander/commander.cpp | 5 ----- src/modules/commander/state_machine_helper.cpp | 22 +++++++++++++++------- 2 files changed, 15 insertions(+), 12 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 27f84116c..d67f184ce 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -2748,11 +2748,6 @@ void *commander_low_prio_loop(void *arg) arming_state_transition(&status, &safety, vehicle_status_s::ARMING_STATE_STANDBY, &armed, true /* fRunPreArmChecks */, mavlink_fd); - /* instruct user to power-cycle */ - if (status.condition_system_sensors_initialized && status.vehicle_status == vehicle_status_s::ARMING_STATE_STANDBY_ERROR) { - mavlink_and_console_log_critical("Calibration successful. Power-cycle the system to complete."); - } - break; } diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 9aba61e14..39892ea01 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -220,14 +220,22 @@ arming_state_transition(struct vehicle_status_s *status, ///< current vehicle s } /* Check if we are trying to arm, checks look good but we are in STANDBY_ERROR */ - if (status->arming_state == vehicle_status_s::ARMING_STATE_STANDBY_ERROR && - new_arming_state == vehicle_status_s::ARMING_STATE_ARMED) { - if (status->condition_system_sensors_initialized) { - mavlink_and_console_log_critical(mavlink_fd, "Preflight check now OK, power cycle before arming"); - } else { - mavlink_and_console_log_critical(mavlink_fd, "Preflight check failed, refusing to arm"); + if (status->arming_state == vehicle_status_s::ARMING_STATE_STANDBY_ERROR) { + + if (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED) { + + if (status->condition_system_sensors_initialized) { + mavlink_and_console_log_critical(mavlink_fd, "Preflight check now OK, power cycle before arming"); + } else { + mavlink_and_console_log_critical(mavlink_fd, "Preflight check failed, refusing to arm"); + } + feedback_provided = true; + + } else if ((new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY) && + status->condition_system_sensors_initialized) { + mavlink_and_console_log_critical(mavlink_fd, "Preflight check resolved, power cycle to complete"); + feedback_provided = true; } - feedback_provided = true; } // Finish up the state transition -- cgit v1.2.3