mirror of https://github.com/ArduPilot/ardupilot
Notify: APM2 arming buzzer to long tone
Arming tone is a solid 3 second tone so it is consistent with Pixhawk arming tone
This commit is contained in:
parent
37b357f282
commit
46e5fa2c0b
|
@ -110,6 +110,20 @@ void Buzzer::update()
|
|||
break;
|
||||
}
|
||||
return;
|
||||
case ARMING_BUZZ:
|
||||
// record start time
|
||||
if (_pattern_counter == 1) {
|
||||
_arming_buzz_start_ms = hal.scheduler->millis();
|
||||
on(true);
|
||||
} else {
|
||||
// turn off buzzer after 3 seconds
|
||||
if (hal.scheduler->millis() - _arming_buzz_start_ms >= BUZZER_ARMING_BUZZ_MS) {
|
||||
_arming_buzz_start_ms = 0;
|
||||
on(false);
|
||||
_pattern = NONE;
|
||||
}
|
||||
}
|
||||
return;
|
||||
default:
|
||||
// do nothing
|
||||
break;
|
||||
|
@ -121,7 +135,7 @@ void Buzzer::update()
|
|||
_flags.armed = AP_Notify::flags.armed;
|
||||
if (_flags.armed) {
|
||||
// double buzz when armed
|
||||
play_pattern(DOUBLE_BUZZ);
|
||||
play_pattern(ARMING_BUZZ);
|
||||
}else{
|
||||
// single buzz when disarmed
|
||||
play_pattern(SINGLE_BUZZ);
|
||||
|
@ -175,4 +189,4 @@ void Buzzer::play_pattern(BuzzerPattern pattern_id)
|
|||
{
|
||||
_pattern = pattern_id;
|
||||
_pattern_counter = 0;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -28,11 +28,18 @@
|
|||
# define BUZZER_PIN 0 // pin undefined on other boards
|
||||
#endif
|
||||
|
||||
#define BUZZER_ARMING_BUZZ_MS 3000 // arming buzz length in milliseconds (i.e. 3 seconds)
|
||||
|
||||
class Buzzer
|
||||
{
|
||||
public:
|
||||
/// Constructor
|
||||
Buzzer() : _counter(0), _pattern(NONE), _pattern_counter(0) {}
|
||||
Buzzer() :
|
||||
_counter(0),
|
||||
_pattern(NONE),
|
||||
_pattern_counter(0),
|
||||
_arming_buzz_start_ms(0)
|
||||
{}
|
||||
|
||||
/// init - initialise the buzzer
|
||||
void init(void);
|
||||
|
@ -47,7 +54,8 @@ public:
|
|||
NONE = 0,
|
||||
SINGLE_BUZZ = 1,
|
||||
DOUBLE_BUZZ = 2,
|
||||
GPS_GLITCH = 3
|
||||
GPS_GLITCH = 3,
|
||||
ARMING_BUZZ = 4
|
||||
};
|
||||
|
||||
/// play_pattern - plays the defined buzzer pattern
|
||||
|
@ -68,6 +76,7 @@ private:
|
|||
uint8_t _counter; // reduces 50hz update down to 10hz for internal processing
|
||||
BuzzerPattern _pattern; // current pattern
|
||||
uint8_t _pattern_counter; // used to time on/off of current patter
|
||||
uint32_t _arming_buzz_start_ms; // arming_buzz start time in milliseconds
|
||||
};
|
||||
|
||||
#endif // __BUZZER_H__
|
||||
|
|
Loading…
Reference in New Issue