mirror of https://github.com/ArduPilot/ardupilot
AP_Notify:correct and expand 1 led flash sequences
This commit is contained in:
parent
bc1e490257
commit
e6351b6a41
|
@ -47,6 +47,8 @@ void GPIO_LED_1::update(void)
|
|||
uint32_t new_pattern;
|
||||
if (AP_Notify::flags.initialising) {
|
||||
new_pattern = INITIALIZING;
|
||||
} else if (AP_Notify::flags.failsafe_radio || AP_Notify::flags.failsafe_gcs || AP_Notify::flags.failsafe_battery) {
|
||||
new pattern = FAILSAFE;
|
||||
} else if (AP_Notify::flags.armed) {
|
||||
new_pattern = ARMED;
|
||||
} else if (AP_Notify::flags.pre_arm_check) {
|
||||
|
|
|
@ -36,9 +36,10 @@ private:
|
|||
|
||||
// left-to-right, each bit represents 100ms
|
||||
static const uint32_t INITIALIZING = 0b10101010101010101010101010101010UL;
|
||||
static const uint32_t NOT_READY_TO_ARM = 0b11111111000000001111111100000000UL;
|
||||
static const uint32_t NOT_READY_TO_ARM = 0b11110000000000001111111110000000UL;
|
||||
static const uint32_t READY_TO_ARM = 0b11111111111111100000000000000000UL;
|
||||
static const uint32_t ARMED = 0b11111111111111111111111111111111UL;
|
||||
static const uint32_t FAILSAFE = 0b11110000111100001111000011110000UL;
|
||||
|
||||
uint32_t current_pattern = INITIALIZING;
|
||||
uint32_t last_timestep_ms;
|
||||
|
|
Loading…
Reference in New Issue