APM:Libraries
ToneAlarm.cpp
Go to the documentation of this file.
1 #include "ToneAlarm.h"
2 
3 #include <fcntl.h>
4 #include <iostream>
5 #include <stdio.h>
6 #include <stdlib.h>
7 #include <sys/stat.h>
8 #include <sys/types.h>
9 #include <unistd.h>
10 
11 #include <AP_HAL/AP_HAL.h>
12 
13 using namespace Linux;
14 
15 extern const AP_HAL::HAL& hal;
16 static uint16_t notes[] = { 0,
21 };
22 
23 //List of RTTTL tones
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 //Tune Repeat true: play rtttl tune in loop, false: play only once
37 bool ToneAlarm::tune_repeat[TONE_NUMBER_OF_TUNES] = {false,true,false,false,false,false,true,true,false,false,false};
38 
40 {
41 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE || \
42  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \
43  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
44  period_fd = open("/sys/devices/ocp.3/pwm_test_P8_36.12/period",O_WRONLY|O_CLOEXEC);
45  duty_fd = open("/sys/devices/ocp.3/pwm_test_P8_36.12/duty",O_WRONLY|O_CLOEXEC);
46  run_fd = open("/sys/devices/ocp.3/pwm_test_P8_36.12/run",O_WRONLY|O_CLOEXEC);
47 #endif
48 
49  tune_num = -1; //initialy no tune to play
50  tune_pos = 0;
51 }
52 
54 {
55  tune_num = 0; //play startup tune
56  if ((period_fd == -1) || (duty_fd == -1) || (run_fd == -1)) {
57 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE || \
58  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \
59  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
60  hal.console->printf("ToneAlarm: Error!! please check if PWM overlays are loaded correctly");
61 #endif
62  return false;
63  }
64  return true;
65 }
66 
67 void ToneAlarm::set_tune(uint8_t tone)
68 {
69  tune_num = tone;
70 }
71 
73 {
74  return tune_comp;
75 }
76 
78 {
79  dprintf(run_fd,"0");
80 }
81 
83 {
84  const uint32_t cur_time = AP_HAL::millis();
85  if(tune_num != prev_tune_num){
86  tune_changed = true;
87  return true;
88  }
89  if(cur_note != 0){
90  dprintf(run_fd,"0");
91  dprintf(period_fd,"%u",1000000000/cur_note);
92  dprintf(duty_fd,"%u",500000000/cur_note);
93  dprintf(run_fd,"1");
94  cur_note =0;
95  prev_time = cur_time;
96  }
97  if((cur_time - prev_time) > duration){
98  stop();
99  if(tune[tune_num][tune_pos] == '\0'){
100  if(!tune_repeat[tune_num]){
101  tune_num = -1;
102  }
103 
104  tune_pos = 0;
105  tune_comp = true;
106  return false;
107  }
108  return true;
109  }
110  return false;
111 }
112 
114  // first, get note duration, if available
115  uint16_t scale,note,num =0;
116  duration = 0;
117 
118  while(isdigit(tune[tune_num][tune_pos])){ //this is a safe while loop as it can't go further than
119  //the length of the rtttl tone string
120  num = (num * 10) + (tune[tune_num][tune_pos++] - '0');
121  }
122  if(num){
123  duration = wholenote / num;
124  } else{
125  duration = wholenote / 4; // we will need to check if we are a dotted note after
126  }
127  // now get the note
128  note = 0;
129 
130  switch(tune[tune_num][tune_pos]){
131  case 'c':
132  note = 1;
133  break;
134  case 'd':
135  note = 3;
136  break;
137  case 'e':
138  note = 5;
139  break;
140  case 'f':
141  note = 6;
142  break;
143  case 'g':
144  note = 8;
145  break;
146  case 'a':
147  note = 10;
148  break;
149  case 'b':
150  note = 12;
151  break;
152  case 'p':
153  default:
154  note = 0;
155  }
156 
157  tune_pos++;
158 
159  // now, get optional '#' sharp
160  if(tune[tune_num][tune_pos] == '#'){
161  note++;
162  tune_pos++;
163  }
164 
165  // now, get optional '.' dotted note
166 
167  if(tune[tune_num][tune_pos] == '.'){
168  duration += duration/2;
169  tune_pos++;
170  }
171 
172  // now, get scale
173 
174  if(isdigit(tune[tune_num][tune_pos])){
175  scale = tune[tune_num][tune_pos] - '0';
176  tune_pos++;
177  } else{
178  scale = default_oct;
179  }
180 
181  scale += OCTAVE_OFFSET;
182 
183  if(tune[tune_num][tune_pos] == ','){
184  tune_pos++; // skip comma for next note (or we may be at the end)
185  }
186  // now play the note
187 
188  if(note){
189  if(tune_changed == true){
190  tune_pos =0;
191  tune_changed = false;
192  }
193  cur_note = notes[(scale - 4) * 12 + note];
194  return true;
195  } else{
196  cur_note = 0;
197  return true;
198  }
199 
200 }
201 
203 
204  uint16_t num;
205  default_dur = 4;
206  default_oct = 6;
207  bpm = 63;
209  if(tune_num <0 || tune_num > TONE_NUMBER_OF_TUNES){
210  return false;
211  }
212 
213  tune_comp = false;
214  while(tune[tune_num][tune_pos] != ':'){
215  if(tune[tune_num][tune_pos] == '\0'){
216  return false;
217  }
218  tune_pos++;
219  }
220  tune_pos++;
221 
222  if(tune[tune_num][tune_pos] == 'd'){
223  tune_pos+=2;
224  num = 0;
225 
226  while(isdigit(tune[tune_num][tune_pos])){
227  num = (num * 10) + (tune[tune_num][tune_pos++] - '0');
228  }
229  if(num > 0){
230  default_dur = num;
231  }
232  tune_pos++; // skip comma
233  }
234 
235 
236  // get default octave
237 
238  if(tune[tune_num][tune_pos] == 'o')
239  {
240  tune_pos+=2; // skip "o="
241  num = tune[tune_num][tune_pos++] - '0';
242  if(num >= 3 && num <=7){
243  default_oct = num;
244  }
245  tune_pos++; // skip comma
246  }
247 
248  // get BPM
249 
250  if(tune[tune_num][tune_pos] == 'b'){
251  tune_pos+=2; // skip "b="
252  num = 0;
253  while(isdigit(tune[tune_num][tune_pos])){
254  num = (num * 10) + (tune[tune_num][tune_pos++] - '0');
255  }
256  bpm = num;
257  tune_pos++; // skip colon
258  }
259 
260  // BPM usually expresses the number of quarter notes per minute
261  wholenote = (60 * 1000L / bpm) * 4; // this is the time for whole note (in milliseconds)
262  return true;
263 }
#define NOTE_G5
Definition: ToneAlarm.h:66
uint8_t default_dur
Definition: ToneAlarm.h:130
#define NOTE_CS5
Definition: ToneAlarm.h:60
#define NOTE_GS5
Definition: ToneAlarm.h:67
int32_t prev_tune_num
Definition: ToneAlarm.h:135
#define NOTE_D5
Definition: ToneAlarm.h:61
#define NOTE_B7
Definition: ToneAlarm.h:94
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define NOTE_FS6
Definition: ToneAlarm.h:77
uint16_t wholenote
Definition: ToneAlarm.h:132
#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
uint16_t duration
Definition: ToneAlarm.h:134
#define NOTE_AS6
Definition: ToneAlarm.h:81
#define NOTE_D6
Definition: ToneAlarm.h:73
static bool tune_repeat[TONE_NUMBER_OF_TUNES]
Definition: ToneAlarm.h:127
#define NOTE_FS5
Definition: ToneAlarm.h:65
#define NOTE_E6
Definition: ToneAlarm.h:75
#define NOTE_DS6
Definition: ToneAlarm.h:74
bool is_tune_comp()
Definition: ToneAlarm.cpp:72
#define NOTE_A5
Definition: ToneAlarm.h:68
#define NOTE_CS7
Definition: ToneAlarm.h:84
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
#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
virtual bool play()
Definition: ToneAlarm.cpp:82
uint8_t default_oct
Definition: ToneAlarm.h:129
static const AP_HAL::HAL & hal
Definition: I2CDevice.cpp:61
#define NOTE_FS7
Definition: ToneAlarm.h:89
#define NOTE_CS6
Definition: ToneAlarm.h:72
uint32_t millis()
Definition: system.cpp:157
void set_tune(uint8_t tone)
Definition: ToneAlarm.cpp:67
#define NOTE_AS7
Definition: ToneAlarm.h:93
#define NOTE_FS4
Definition: ToneAlarm.h:53
uint8_t tune_pos
Definition: ToneAlarm.h:138
uint16_t cur_note
Definition: ToneAlarm.h:133
#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
uint16_t bpm
Definition: ToneAlarm.h:131
virtual bool init()
Definition: ToneAlarm.cpp:53
#define OCTAVE_OFFSET
Definition: ToneAlarm.h:8
static const char * tune[TONE_NUMBER_OF_TUNES]
Definition: ToneAlarm.h:126
#define NOTE_E7
Definition: ToneAlarm.h:87
#define NOTE_E5
Definition: ToneAlarm.h:63
#define NOTE_G4
Definition: ToneAlarm.h:54
uint32_t prev_time
Definition: ToneAlarm.h:136
#define NOTE_F6
Definition: ToneAlarm.h:76
#define NOTE_F5
Definition: ToneAlarm.h:64
int32_t run_fd
Definition: ToneAlarm.h:143
#define NOTE_CS4
Definition: ToneAlarm.h:48
#define NOTE_C6
Definition: ToneAlarm.h:71
int32_t period_fd
Definition: ToneAlarm.h:141
#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
int32_t duty_fd
Definition: ToneAlarm.h:142
#define NOTE_D7
Definition: ToneAlarm.h:85
virtual void stop()
Definition: ToneAlarm.cpp:77