mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 15:40:31 +08:00
commander status flags delete condition_system_prearm_error_reported
- this flag often results in hiding useful information, or adding useless information to the mavlink console
This commit is contained in:
@@ -2,7 +2,6 @@
|
||||
|
||||
bool condition_calibration_enabled
|
||||
bool condition_system_sensors_initialized
|
||||
bool condition_system_prearm_error_reported # true if errors have already been reported
|
||||
bool condition_system_hotplug_timeout # true if the hotplug sensor search is over
|
||||
bool condition_system_returned_to_home
|
||||
bool condition_auto_mission_available
|
||||
|
||||
@@ -284,14 +284,6 @@ transition_result_t arming_state_transition(vehicle_status_s *status, const batt
|
||||
(status->arming_state != vehicle_status_s::ARMING_STATE_STANDBY_ERROR)) {
|
||||
|
||||
if (!status_flags->condition_system_sensors_initialized) {
|
||||
|
||||
if (status_flags->condition_system_hotplug_timeout) {
|
||||
if (!status_flags->condition_system_prearm_error_reported) {
|
||||
mavlink_log_critical(mavlink_log_pub, "Not ready to fly: Sensors not set up correctly");
|
||||
status_flags->condition_system_prearm_error_reported = true;
|
||||
}
|
||||
}
|
||||
|
||||
feedback_provided = true;
|
||||
valid_transition = false;
|
||||
}
|
||||
@@ -321,13 +313,6 @@ transition_result_t arming_state_transition(vehicle_status_s *status, const batt
|
||||
}
|
||||
}
|
||||
|
||||
/* reset feedback state */
|
||||
if (status->arming_state != vehicle_status_s::ARMING_STATE_STANDBY_ERROR &&
|
||||
status->arming_state != vehicle_status_s::ARMING_STATE_INIT &&
|
||||
valid_transition) {
|
||||
status_flags->condition_system_prearm_error_reported = false;
|
||||
}
|
||||
|
||||
/* end of atomic state update */
|
||||
#ifdef __PX4_NUTTX
|
||||
px4_leave_critical_section(flags);
|
||||
|
||||
Reference in New Issue
Block a user