mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: whitespace change
This commit is contained in:
parent
f5b4a482b0
commit
4a6cc75ebb
@ -227,27 +227,27 @@ private:
|
||||
// Documentation of GLobals:
|
||||
union {
|
||||
struct {
|
||||
uint8_t unused1 : 1; // 0
|
||||
uint8_t simple_mode : 2; // 1,2 // This is the state of simple mode : 0 = disabled ; 1 = SIMPLE ; 2 = SUPERSIMPLE
|
||||
uint8_t pre_arm_rc_check : 1; // 3 // true if rc input pre-arm checks have been completed successfully
|
||||
uint8_t pre_arm_check : 1; // 4 // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
|
||||
uint8_t auto_armed : 1; // 5 // stops auto missions from beginning until throttle is raised
|
||||
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 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_emergency_stop: 1; // 21 // motor estop switch, shuts off motors when enabled
|
||||
uint8_t land_repo_active : 1; // 22 // true if the pilot is overriding the landing position
|
||||
uint8_t unused1 : 1; // 0
|
||||
uint8_t simple_mode : 2; // 1,2 // This is the state of simple mode : 0 = disabled ; 1 = SIMPLE ; 2 = SUPERSIMPLE
|
||||
uint8_t pre_arm_rc_check : 1; // 3 // true if rc input pre-arm checks have been completed successfully
|
||||
uint8_t pre_arm_check : 1; // 4 // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
|
||||
uint8_t auto_armed : 1; // 5 // stops auto missions from beginning until throttle is raised
|
||||
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 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_emergency_stop : 1; // 21 // motor estop switch, shuts off motors when enabled
|
||||
uint8_t land_repo_active : 1; // 22 // true if the pilot is overriding the landing position
|
||||
};
|
||||
uint32_t value;
|
||||
} ap;
|
||||
|
Loading…
Reference in New Issue
Block a user