@ -341,24 +341,18 @@ static union {
@@ -341,24 +341,18 @@ static union {
uint8_t logging_started : 1; // 6 // true if dataflash logging has started
uint8_t land_complete : 1; // 7 // true if we have detected a landing
uint8_t new_radio_frame : 1; // 8 // Set true if we have new PWM data to act on from the Radio
uint8_t CH7_flag : 2; // 9,10 // ch7 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t CH8_flag : 2; // 11,12 // ch8 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t CH9_flag : 2; // 13,14 // ch9 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t CH10_flag : 2; // 15,16 // ch10 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t CH11_flag : 2; // 17,18 // ch11 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t CH12_flag : 2; // 19,20 // ch12 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t usb_connected : 1; // 21 // true if APM is powered from USB connection
uint8_t rc_receiver_present : 1; // 22 // true if we have an rc receiver present (i.e. if we've ever received an update
uint8_t compass_mot : 1; // 23 // true if we are currently performing compassmot calibration
uint8_t motor_test : 1; // 24 // true if we are currently performing the motors test
uint8_t initialised : 1; // 25 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
uint8_t land_complete_maybe : 1; // 26 // true if we may have landed (less strict version of land_complete)
uint8_t throttle_zero : 1; // 27 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
uint8_t system_time_set : 1; // 28 // true if the system time has been set from the GPS
uint8_t gps_base_pos_set : 1; // 29 // true when the gps base position has been set (used for RTK gps only)
enum HomeState home_state : 2; // 30,31 // home status (unset, set, locked)
uint8_t using_interlock : 1; // 32 // aux switch motor interlock function is in use
uint8_t motor_estop : 1; // 33 // motor estop switch, shuts off motors when enabled
uint8_t usb_connected : 1; // 9 // true if APM is powered from USB connection
uint8_t rc_receiver_present : 1; // 10 // true if we have an rc receiver present (i.e. if we've ever received an update
uint8_t compass_mot : 1; // 11 // true if we are currently performing compassmot calibration
uint8_t motor_test : 1; // 12 // true if we are currently performing the motors test
uint8_t initialised : 1; // 13 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
uint8_t land_complete_maybe : 1; // 14 // true if we may have landed (less strict version of land_complete)
uint8_t throttle_zero : 1; // 15 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
uint8_t system_time_set : 1; // 16 // true if the system time has been set from the GPS
uint8_t gps_base_pos_set : 1; // 17 // true when the gps base position has been set (used for RTK gps only)
enum HomeState home_state : 2; // 18,19 // home status (unset, set, locked)
uint8_t using_interlock : 1; // 20 // aux switch motor interlock function is in use
uint8_t motor_estop : 1; // 21 // motor estop switch, shuts off motors when enabled