commander: Provide feedback that preflight check failed.

This commit is contained in:
Lorenz Meier 2015-04-20 09:13:31 +02:00
parent 17e487cad4
commit 0a526e2a5f
1 changed files with 6 additions and 3 deletions

View File

@ -219,9 +219,12 @@ 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 &&
status->condition_system_sensors_initialized) {
mavlink_log_critical(mavlink_fd, "Preflight check now OK, power cycle before arming");
new_arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
if (status->condition_system_sensors_initialized) {
mavlink_log_critical(mavlink_fd, "Preflight check now OK, power cycle before arming");
} else {
mavlink_log_critical(mavlink_fd, "Preflight check failed, refusing to arm");
}
feedback_provided = true;
}