mirror of https://github.com/ArduPilot/ardupilot
AP_Notify: reorder flags
This tiny improvement allows the flags above battery voltage to be squeezed into the same byte
This commit is contained in:
parent
e085ae1ec8
commit
cb1d1df03a
|
@ -57,7 +57,6 @@ public:
|
|||
uint32_t initialising : 1; // 1 if initialising and copter should not be moved
|
||||
uint32_t gps_status : 3; // 0 = no gps, 1 = no lock, 2 = 2d lock, 3 = 3d lock, 4 = dgps lock, 5 = rtk lock
|
||||
uint32_t gps_num_sats : 6; // number of sats
|
||||
float battery_voltage ; // battery voltage
|
||||
uint32_t flight_mode : 8; // flight mode
|
||||
uint32_t armed : 1; // 0 = disarmed, 1 = armed
|
||||
uint32_t pre_arm_check : 1; // 0 = failing checks, 1 = passed
|
||||
|
@ -71,6 +70,7 @@ public:
|
|||
uint32_t autopilot_mode : 1; // 1 if vehicle is in an autopilot flight mode (only used by OreoLEDs)
|
||||
uint32_t firmware_update : 1; // 1 just before vehicle firmware is updated
|
||||
uint32_t compass_cal_running: 1; // 1 if a compass calibration is running
|
||||
float battery_voltage ; // battery voltage
|
||||
|
||||
// additional flags
|
||||
uint32_t external_leds : 1; // 1 if external LEDs are enabled (normally only used for copter)
|
||||
|
|
Loading…
Reference in New Issue