10 struct ToneAlarm::pwmGroup ToneAlarm::pwm_group = HAL_PWM_ALARM;
12 #define isdigit(n) (n >= '0' && n <= '9') 16 static uint16_t
notes[] = { 0,
17 NOTE_C4,
NOTE_CS4,
NOTE_D4,
NOTE_DS4,
NOTE_E4,
NOTE_F4,
NOTE_FS4,
NOTE_G4,
NOTE_GS4,
NOTE_A4,
NOTE_AS4,
NOTE_B4,
18 NOTE_C5,
NOTE_CS5,
NOTE_D5,
NOTE_DS5,
NOTE_E5,
NOTE_F5,
NOTE_FS5,
NOTE_G5,
NOTE_GS5,
NOTE_A5,
NOTE_AS5,
NOTE_B5,
19 NOTE_C6,
NOTE_CS6,
NOTE_D6,
NOTE_DS6,
NOTE_E6,
NOTE_F6,
NOTE_FS6,
NOTE_G6,
NOTE_GS6,
NOTE_A6,
NOTE_AS6,
NOTE_B6,
20 NOTE_C7,
NOTE_CS7,
NOTE_D7,
NOTE_DS7,
NOTE_E7,
NOTE_F7,
NOTE_FS7,
NOTE_G7,
NOTE_GS7,
NOTE_A7,
NOTE_AS7,
NOTE_B7 25 "Startup:d=8,o=6,b=480:a,d7,c7,a,d7,c7,a,d7,16d7,16c7,16d7,16c7,16d7,16c7,16d7,16c7",
26 "Error:d=4,o=6,b=400:8a,8a,8a,p,a,a,a,p",
27 "notify_pos:d=4,o=6,b=400:8e,8e,a",
28 "notify_neut:d=4,o=6,b=400:8e,e",
29 "notify_neg:d=4,o=6,b=400:8e,8c,8e,8c,8e,8c",
30 "arming_warn:d=1,o=4,b=75:g",
31 "batt_war_slow:d=4,o=6,b=200:8a",
32 "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",
33 "GPS_war:d=4,o=6,b=512:a,a,a,1f#",
34 "Arm_fail:d=4,o=4,b=512:b,a,p",
35 "para_rel:d=16,o=6,b=512:a,g,a,g,a,g,a,g",
36 "modechangeloud:d=4,o=6,b=400:8e",
37 "modechangesoft:d=4,o=6,b=400:8e",
41 bool ToneAlarm::tune_repeat[
TONE_NUMBER_OF_TUNES] = {
false,
true,
false,
false,
false,
false,
true,
true,
false,
false,
false};
43 ToneAlarm::ToneAlarm()
52 pwm_group.pwm_cfg.period = 1000;
53 pwmStart(pwm_group.pwm_drv, &pwm_group.pwm_cfg);
60 void ToneAlarm::set_tune(uint8_t tone)
65 bool ToneAlarm::is_tune_comp()
70 void ToneAlarm::stop()
72 pwmDisableChannel(pwm_group.pwm_drv, pwm_group.chan);
76 bool ToneAlarm::play()
79 if(tune_num != prev_tune_num) {
88 pwmChangePeriod(pwm_group.pwm_drv,
89 pwm_group.pwm_cfg.frequency/cur_note);
91 pwmEnableChannel(pwm_group.pwm_drv, pwm_group.chan,
92 (pwm_group.pwm_cfg.frequency/2)/cur_note);
98 if((cur_time - prev_time) > duration) {
102 if(tune[tune_num][tune_pos] ==
'\0') {
105 if(!tune_repeat[tune_num]){
120 bool ToneAlarm::set_note()
123 uint16_t scale,note,
num =0;
126 while(isdigit(tune[tune_num][tune_pos])){
128 num = (num * 10) + (tune[tune_num][tune_pos++] -
'0');
131 duration = wholenote /
num;
133 duration = wholenote / 4;
138 switch(tune[tune_num][tune_pos]){
168 if(tune[tune_num][tune_pos] ==
'#'){
175 if(tune[tune_num][tune_pos] ==
'.'){
176 duration += duration/2;
182 if(isdigit(tune[tune_num][tune_pos])){
183 scale = tune[tune_num][tune_pos] -
'0';
191 if(tune[tune_num][tune_pos] ==
','){
197 cur_note =
notes[(scale - 4) * 12 + note];
206 bool ToneAlarm::init_tune()
212 prev_tune_num = tune_num;
213 tune_changed =
false;
219 while(tune[tune_num][tune_pos] !=
':'){
220 if(tune[tune_num][tune_pos] ==
'\0'){
227 if(tune[tune_num][tune_pos] ==
'd'){
231 while(isdigit(tune[tune_num][tune_pos])){
232 num = (num * 10) + (tune[tune_num][tune_pos++] -
'0');
243 if(tune[tune_num][tune_pos] ==
'o')
246 num = tune[tune_num][tune_pos++] -
'0';
247 if(num >= 3 && num <=7){
255 if(tune[tune_num][tune_pos] ==
'b'){
258 while(isdigit(tune[tune_num][tune_pos])){
259 num = (num * 10) + (tune[tune_num][tune_pos++] -
'0');
266 wholenote = (60 * 1000L / bpm) * 4;
#define TONE_NUMBER_OF_TUNES
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void init()
Generic board initialization function.