mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 02:55:07 +08:00
add low battery warning and comment out the "resolved" messages
This commit is contained in:
committed by
Lorenz Meier
parent
b4520f538e
commit
817c0eafbc
@@ -95,7 +95,7 @@ static const bool arming_transitions[vehicle_status_s::ARMING_STATE_MAX][vehicle
|
|||||||
{ /* vehicle_status_s::ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false, false }, // NYI
|
{ /* vehicle_status_s::ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false, false }, // NYI
|
||||||
};
|
};
|
||||||
|
|
||||||
// You can index into the array with an arming_state_t in order to get it's textual representation
|
// You can index into the array with an arming_state_t in order to get its textual representation
|
||||||
static const char * const state_names[vehicle_status_s::ARMING_STATE_MAX] = {
|
static const char * const state_names[vehicle_status_s::ARMING_STATE_MAX] = {
|
||||||
"ARMING_STATE_INIT",
|
"ARMING_STATE_INIT",
|
||||||
"ARMING_STATE_STANDBY",
|
"ARMING_STATE_STANDBY",
|
||||||
@@ -254,7 +254,7 @@ arming_state_transition(struct vehicle_status_s *status, ///< current vehicle s
|
|||||||
if (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
|
if (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
|
||||||
|
|
||||||
if (status->condition_system_sensors_initialized) {
|
if (status->condition_system_sensors_initialized) {
|
||||||
mavlink_and_console_log_critical(mavlink_log_pub, "Preflight check resolved, reboot before arming");
|
// mavlink_and_console_log_critical(mavlink_log_pub, "Preflight check resolved, reboot before arming");
|
||||||
} else {
|
} else {
|
||||||
mavlink_and_console_log_critical(mavlink_log_pub, "Preflight check failed, refusing to arm");
|
mavlink_and_console_log_critical(mavlink_log_pub, "Preflight check failed, refusing to arm");
|
||||||
}
|
}
|
||||||
@@ -262,7 +262,7 @@ arming_state_transition(struct vehicle_status_s *status, ///< current vehicle s
|
|||||||
|
|
||||||
} else if ((new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY) &&
|
} else if ((new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY) &&
|
||||||
status->condition_system_sensors_initialized) {
|
status->condition_system_sensors_initialized) {
|
||||||
mavlink_and_console_log_critical(mavlink_log_pub, "Preflight check resolved, reboot to complete");
|
// mavlink_and_console_log_critical(mavlink_log_pub, "Preflight check resolved, reboot to complete");
|
||||||
feedback_provided = true;
|
feedback_provided = true;
|
||||||
} else {
|
} else {
|
||||||
// Silent ignore
|
// Silent ignore
|
||||||
@@ -885,6 +885,11 @@ int preflight_check(struct vehicle_status_s *status, orb_advert_t *mavlink_log_p
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (status->battery_warning == vehicle_status_s::VEHICLE_BATTERY_WARNING_CRITICAL) {
|
||||||
|
preflight_ok = false;
|
||||||
|
mavlink_and_console_log_critical(mavlink_log_pub, "LOW BATTERY, ARMING LOCKED DOWN");
|
||||||
|
}
|
||||||
|
|
||||||
/* report once, then set the flag */
|
/* report once, then set the flag */
|
||||||
if (reportFailures && !preflight_ok) {
|
if (reportFailures && !preflight_ok) {
|
||||||
status->condition_system_prearm_error_reported = true;
|
status->condition_system_prearm_error_reported = true;
|
||||||
|
|||||||
Reference in New Issue
Block a user