mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_Notify: add buzzer noises
This commit is contained in:
parent
00858dce78
commit
ec1d29d806
@ -123,6 +123,7 @@ public:
|
||||
bool powering_off; // true when the vehicle is powering off
|
||||
bool video_recording; // true when the vehicle is recording video
|
||||
bool temp_cal_running; // true if a temperature calibration is running
|
||||
bool gyro_calibrated; // true if calibrated gyro/acc
|
||||
};
|
||||
|
||||
/// notify_events_type - bitmask of active events.
|
||||
|
@ -66,6 +66,18 @@ void Buzzer::update_pattern_to_play()
|
||||
return;
|
||||
}
|
||||
|
||||
// initializing?
|
||||
if (_flags.gyro_calibrated != AP_Notify::flags.gyro_calibrated) {
|
||||
_flags.gyro_calibrated = AP_Notify::flags.gyro_calibrated;
|
||||
play_pattern(INIT_GYRO);
|
||||
}
|
||||
|
||||
// check if prearm check are good
|
||||
if (AP_Notify::flags.pre_arm_check && !_flags.pre_arm_check) {
|
||||
_flags.pre_arm_check = true;
|
||||
play_pattern(PRE_ARM_GOOD);
|
||||
}
|
||||
|
||||
// check if armed status has changed
|
||||
if (_flags.armed != AP_Notify::flags.armed) {
|
||||
_flags.armed = AP_Notify::flags.armed;
|
||||
|
@ -43,6 +43,8 @@ private:
|
||||
static const uint32_t ARMING_BUZZ = 0b11111111111111111111111111111100UL; // 3s
|
||||
static const uint32_t BARO_BUZZ = 0b10101010100000000000000000000000UL;
|
||||
static const uint32_t EKF_BAD = 0b11101101010000000000000000000000UL;
|
||||
static const uint32_t INIT_GYRO = 0b10010010010010010010000000000000UL;
|
||||
static const uint32_t PRE_ARM_GOOD = 0b10101011111111110000000000000000UL;
|
||||
|
||||
/// play_pattern - plays the defined buzzer pattern
|
||||
void play_pattern(const uint32_t pattern);
|
||||
@ -54,6 +56,8 @@ private:
|
||||
uint8_t armed : 1; // 0 = disarmed, 1 = armed
|
||||
uint8_t failsafe_battery : 1; // 1 if battery failsafe has triggered
|
||||
uint8_t ekf_bad : 1; // 1 if ekf position has gone bad
|
||||
uint8_t gyro_calibrated : 1; // 1 if calibrating gyro
|
||||
uint8_t pre_arm_check : 1; // 1 if pre-arm check has passed
|
||||
} _flags;
|
||||
|
||||
uint32_t _pattern; // current pattern
|
||||
|
Loading…
Reference in New Issue
Block a user