diff --git a/msg/vehicle_status_flags.msg b/msg/vehicle_status_flags.msg index 584d439eac..9d72de0751 100644 --- a/msg/vehicle_status_flags.msg +++ b/msg/vehicle_status_flags.msg @@ -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 diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index af2f4a2cb8..44798dc790 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -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);