APM:Libraries
ToneAlarm.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
3 
4 #ifdef HAL_PWM_ALARM
5 
6 #include "ToneAlarm.h"
7 
8 using namespace ChibiOS;
9 
10 struct ToneAlarm::pwmGroup ToneAlarm::pwm_group = HAL_PWM_ALARM;
11 
12 #define isdigit(n) (n >= '0' && n <= '9')
13 
14 extern const AP_HAL::HAL& hal;
15 
16 static uint16_t notes[] = { 0,
21 };
22 
23 //List of RTTTL tones
24 const char* ToneAlarm::tune[TONE_NUMBER_OF_TUNES] = {
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",
38 };
39 
40 //Tune Repeat true: play rtttl tune in loop, false: play only once
41 bool ToneAlarm::tune_repeat[TONE_NUMBER_OF_TUNES] = {false,true,false,false,false,false,true,true,false,false,false};
42 
43 ToneAlarm::ToneAlarm()
44 {
45  tune_num = -1; //initially no tune to play
46  tune_pos = 0;
47 }
48 
49 bool ToneAlarm::init()
50 {
51  // start PWM driver
52  pwm_group.pwm_cfg.period = 1000;
53  pwmStart(pwm_group.pwm_drv, &pwm_group.pwm_cfg);
54 
55  tune_num = 0; //play startup tune
56 
57  return true;
58 }
59 
60 void ToneAlarm::set_tune(uint8_t tone)
61 {
62  tune_num = tone;
63 }
64 
65 bool ToneAlarm::is_tune_comp()
66 {
67  return tune_comp;
68 }
69 
70 void ToneAlarm::stop()
71 {
72  pwmDisableChannel(pwm_group.pwm_drv, pwm_group.chan);
73 
74 }
75 
76 bool ToneAlarm::play()
77 {
78  const uint32_t cur_time = AP_HAL::millis();
79  if(tune_num != prev_tune_num) {
80  stop();
81  tune_changed = true;
82  tune_pos = 0;
83  tune_comp = true;
84  return false;
85  }
86  if(cur_note != 0) {
87  // specify alarm timer and channel in hwdef.dat
88  pwmChangePeriod(pwm_group.pwm_drv,
89  pwm_group.pwm_cfg.frequency/cur_note);
90 
91  pwmEnableChannel(pwm_group.pwm_drv, pwm_group.chan,
92  (pwm_group.pwm_cfg.frequency/2)/cur_note);
93 
94  cur_note = 0;
95  prev_time = cur_time;
96  }
97  // has note duration elapsed?
98  if((cur_time - prev_time) > duration) {
99  // yes, stop the PWM signal
100  stop();
101  // was that the last note?
102  if(tune[tune_num][tune_pos] == '\0') {
103  // this was the last note
104  // if this is not a repeating tune, disable playback
105  if(!tune_repeat[tune_num]){
106  tune_num = -1;
107  }
108  // reset tune spec index to zero: this is the only place tune_pos is reset
109  tune_pos = 0;
110  tune_comp = true;
111  // indicate tune is complete by returning false
112  return false;
113  }
114  // indicate tune is still playing by returning true
115  return true;
116  }
117  return false;
118 }
119 
120 bool ToneAlarm::set_note()
121 {
122  // first, get note duration, if available
123  uint16_t scale,note,num =0;
124  duration = 0;
125 
126  while(isdigit(tune[tune_num][tune_pos])){ //this is a safe while loop as it can't go further than
127  //the length of the rtttl tone string
128  num = (num * 10) + (tune[tune_num][tune_pos++] - '0');
129  }
130  if(num){
131  duration = wholenote / num;
132  } else{
133  duration = wholenote / 4; // we will need to check if we are a dotted note after
134  }
135  // now get the note
136  note = 0;
137 
138  switch(tune[tune_num][tune_pos]){
139  case 'c':
140  note = 1;
141  break;
142  case 'd':
143  note = 3;
144  break;
145  case 'e':
146  note = 5;
147  break;
148  case 'f':
149  note = 6;
150  break;
151  case 'g':
152  note = 8;
153  break;
154  case 'a':
155  note = 10;
156  break;
157  case 'b':
158  note = 12;
159  break;
160  case 'p':
161  default:
162  note = 0;
163  }
164 
165  tune_pos++;
166 
167  // now, get optional '#' sharp
168  if(tune[tune_num][tune_pos] == '#'){
169  note++;
170  tune_pos++;
171  }
172 
173  // now, get optional '.' dotted note
174 
175  if(tune[tune_num][tune_pos] == '.'){
176  duration += duration/2;
177  tune_pos++;
178  }
179 
180  // now, get scale
181 
182  if(isdigit(tune[tune_num][tune_pos])){
183  scale = tune[tune_num][tune_pos] - '0';
184  tune_pos++;
185  } else{
186  scale = default_oct;
187  }
188 
189  scale += OCTAVE_OFFSET;
190 
191  if(tune[tune_num][tune_pos] == ','){
192  tune_pos++; // skip comma for next note (or we may be at the end)
193  }
194  // now play the note
195 
196  if(note){
197  cur_note = notes[(scale - 4) * 12 + note];
198  return true;
199  } else{
200  cur_note = 0;
201  return true;
202  }
203 
204 }
205 
206 bool ToneAlarm::init_tune()
207 {
208  uint16_t num;
209  default_dur = 4;
210  default_oct = 6;
211  bpm = 63;
212  prev_tune_num = tune_num;
213  tune_changed = false;
214  if(tune_num <0 || tune_num > TONE_NUMBER_OF_TUNES){
215  return false;
216  }
217 
218  tune_comp = false;
219  while(tune[tune_num][tune_pos] != ':'){
220  if(tune[tune_num][tune_pos] == '\0'){
221  return false;
222  }
223  tune_pos++;
224  }
225  tune_pos++;
226 
227  if(tune[tune_num][tune_pos] == 'd'){
228  tune_pos+=2;
229  num = 0;
230 
231  while(isdigit(tune[tune_num][tune_pos])){
232  num = (num * 10) + (tune[tune_num][tune_pos++] - '0');
233  }
234  if(num > 0){
235  default_dur = num;
236  }
237  tune_pos++; // skip comma
238  }
239 
240 
241  // get default octave
242 
243  if(tune[tune_num][tune_pos] == 'o')
244  {
245  tune_pos+=2; // skip "o="
246  num = tune[tune_num][tune_pos++] - '0';
247  if(num >= 3 && num <=7){
248  default_oct = num;
249  }
250  tune_pos++; // skip comma
251  }
252 
253  // get BPM
254 
255  if(tune[tune_num][tune_pos] == 'b'){
256  tune_pos+=2; // skip "b="
257  num = 0;
258  while(isdigit(tune[tune_num][tune_pos])){
259  num = (num * 10) + (tune[tune_num][tune_pos++] - '0');
260  }
261  bpm = num;
262  tune_pos++; // skip colon
263  }
264 
265  // BPM usually expresses the number of quarter notes per minute
266  wholenote = (60 * 1000L / bpm) * 4; // this is the time for whole note (in milliseconds)
267 
268  return true;
269 }
270 #endif
#define NOTE_G5
Definition: ToneAlarm.h:66
#define NOTE_CS5
Definition: ToneAlarm.h:60
#define NOTE_GS5
Definition: ToneAlarm.h:67
#define NOTE_D5
Definition: ToneAlarm.h:61
#define NOTE_B7
Definition: ToneAlarm.h:94
#define NOTE_FS6
Definition: ToneAlarm.h:77
#define NOTE_GS4
Definition: ToneAlarm.h:55
#define NOTE_DS5
Definition: ToneAlarm.h:62
#define NOTE_C4
Definition: ToneAlarm.h:47
#define NOTE_B6
Definition: ToneAlarm.h:82
#define NOTE_G6
Definition: ToneAlarm.h:78
#define NOTE_AS6
Definition: ToneAlarm.h:81
#define NOTE_D6
Definition: ToneAlarm.h:73
#define NOTE_FS5
Definition: ToneAlarm.h:65
#define NOTE_E6
Definition: ToneAlarm.h:75
#define NOTE_DS6
Definition: ToneAlarm.h:74
#define NOTE_A5
Definition: ToneAlarm.h:68
#define NOTE_CS7
Definition: ToneAlarm.h:84
#define NOTE_AS5
Definition: ToneAlarm.h:69
#define NOTE_B5
Definition: ToneAlarm.h:70
static uint16_t notes[]
Definition: ToneAlarm.cpp:16
#define NOTE_A6
Definition: ToneAlarm.h:80
#define NOTE_C5
Definition: ToneAlarm.h:59
#define TONE_NUMBER_OF_TUNES
Definition: ToneAlarm.h:114
#define NOTE_C7
Definition: ToneAlarm.h:83
#define NOTE_AS4
Definition: ToneAlarm.h:57
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define NOTE_FS7
Definition: ToneAlarm.h:89
#define NOTE_CS6
Definition: ToneAlarm.h:72
uint32_t millis()
Definition: system.cpp:157
#define NOTE_AS7
Definition: ToneAlarm.h:93
#define NOTE_FS4
Definition: ToneAlarm.h:53
#define NOTE_F7
Definition: ToneAlarm.h:88
#define NOTE_G7
Definition: ToneAlarm.h:90
#define NOTE_A7
Definition: ToneAlarm.h:92
#define NOTE_D4
Definition: ToneAlarm.h:49
#define NOTE_GS6
Definition: ToneAlarm.h:79
#define NOTE_DS7
Definition: ToneAlarm.h:86
#define OCTAVE_OFFSET
Definition: ToneAlarm.h:8
#define NOTE_E7
Definition: ToneAlarm.h:87
#define NOTE_E5
Definition: ToneAlarm.h:63
#define NOTE_G4
Definition: ToneAlarm.h:54
#define NOTE_F6
Definition: ToneAlarm.h:76
#define NOTE_F5
Definition: ToneAlarm.h:64
void init()
Generic board initialization function.
Definition: system.cpp:136
#define NOTE_CS4
Definition: ToneAlarm.h:48
#define NOTE_C6
Definition: ToneAlarm.h:71
#define NOTE_A4
Definition: ToneAlarm.h:56
void uint32_t num
Definition: systick.h:80
#define NOTE_F4
Definition: ToneAlarm.h:52
#define NOTE_DS4
Definition: ToneAlarm.h:50
#define NOTE_E4
Definition: ToneAlarm.h:51
#define NOTE_GS7
Definition: ToneAlarm.h:91
#define NOTE_B4
Definition: ToneAlarm.h:58
#define NOTE_D7
Definition: ToneAlarm.h:85