mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_HAL_ChibiOS: add mode-change-beeps
This commit is contained in:
parent
79f3fd532b
commit
557f8cee43
@ -32,7 +32,10 @@ const char* ToneAlarm::tune[TONE_NUMBER_OF_TUNES] = {
|
|||||||
"batt_war_fast:d=4,o=6,b=512:8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a",
|
"batt_war_fast:d=4,o=6,b=512:8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a,8a",
|
||||||
"GPS_war:d=4,o=6,b=512:a,a,a,1f#",
|
"GPS_war:d=4,o=6,b=512:a,a,a,1f#",
|
||||||
"Arm_fail:d=4,o=4,b=512:b,a,p",
|
"Arm_fail:d=4,o=4,b=512:b,a,p",
|
||||||
"para_rel:d=16,o=6,b=512:a,g,a,g,a,g,a,g"};
|
"para_rel:d=16,o=6,b=512:a,g,a,g,a,g,a,g",
|
||||||
|
"modechangeloud:d=4,o=6,b=400:8e",
|
||||||
|
"modechangesoft:d=4,o=6,b=400:8e",
|
||||||
|
};
|
||||||
|
|
||||||
//Tune Repeat true: play rtttl tune in loop, false: play only once
|
//Tune Repeat true: play rtttl tune in loop, false: play only once
|
||||||
bool ToneAlarm::tune_repeat[TONE_NUMBER_OF_TUNES] = {false,true,false,false,false,false,true,true,false,false,false};
|
bool ToneAlarm::tune_repeat[TONE_NUMBER_OF_TUNES] = {false,true,false,false,false,false,true,true,false,false,false};
|
||||||
|
@ -108,8 +108,10 @@
|
|||||||
#define TONE_GPS_WARNING_TUNE 8
|
#define TONE_GPS_WARNING_TUNE 8
|
||||||
#define TONE_ARMING_FAILURE_TUNE 9
|
#define TONE_ARMING_FAILURE_TUNE 9
|
||||||
#define TONE_PARACHUTE_RELEASE_TUNE 10
|
#define TONE_PARACHUTE_RELEASE_TUNE 10
|
||||||
|
#define TONE_NOTIFY_MODE_CHANGE_LOUD 11
|
||||||
|
#define TONE_NOTIFY_MODE_CHANGE_SOFT 12
|
||||||
|
|
||||||
#define TONE_NUMBER_OF_TUNES 11
|
#define TONE_NUMBER_OF_TUNES 13
|
||||||
|
|
||||||
#ifdef HAL_PWM_ALARM
|
#ifdef HAL_PWM_ALARM
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user