|
|
|
@ -211,7 +211,7 @@ arming_state_transition(struct vehicle_status_s *status, ///< current vehicle s
@@ -211,7 +211,7 @@ arming_state_transition(struct vehicle_status_s *status, ///< current vehicle s
|
|
|
|
|
valid_transition = true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* Sensors need to be initialized for STANDBY state */ |
|
|
|
|
// Sensors need to be initialized for STANDBY state
|
|
|
|
|
if (new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY && !status->condition_system_sensors_initialized) { |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "Not ready to fly: Sensors not operational."); |
|
|
|
|
feedback_provided = true; |
|
|
|
@ -219,15 +219,23 @@ arming_state_transition(struct vehicle_status_s *status, ///< current vehicle s
@@ -219,15 +219,23 @@ arming_state_transition(struct vehicle_status_s *status, ///< current vehicle s
|
|
|
|
|
status->arming_state = vehicle_status_s::ARMING_STATE_STANDBY_ERROR; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* 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"); |
|
|
|
|
// 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) { |
|
|
|
|
|
|
|
|
|
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
|
|
|
|
|