MMLPlayer.cpp 6.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307
  1. #include "MMLPlayer.h"
  2. #include <ctype.h>
  3. #include <math.h>
  4. #include <AP_HAL/AP_HAL.h>
  5. #include <AP_Math/AP_Math.h>
  6. #include <AP_Notify/AP_Notify.h>
  7. #if HAL_WITH_UAVCAN
  8. #include <AP_UAVCAN/AP_UAVCAN.h>
  9. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  10. #endif
  11. extern const AP_HAL::HAL& hal;
  12. void MMLPlayer::update()
  13. {
  14. // Check if note is over
  15. if (_playing && AP_HAL::micros()-_note_start_us > _note_duration_us) {
  16. next_action();
  17. }
  18. }
  19. void MMLPlayer::play(const char* string)
  20. {
  21. stop();
  22. _string = string;
  23. _next = 0;
  24. _tempo = 120;
  25. _default_note_length = 4;
  26. _note_mode = MODE_NORMAL;
  27. _octave = 4;
  28. _volume = 255;
  29. _silence_duration = 0;
  30. _repeat = false;
  31. _playing = true;
  32. next_action();
  33. }
  34. void MMLPlayer::stop()
  35. {
  36. _playing = false;
  37. hal.util->toneAlarm_set_buzzer_tone(0,0,0);
  38. }
  39. void MMLPlayer::start_silence(float duration)
  40. {
  41. _note_start_us = AP_HAL::micros();
  42. _note_duration_us = duration*1e6;
  43. hal.util->toneAlarm_set_buzzer_tone(0, 0, 0);
  44. }
  45. void MMLPlayer::start_note(float duration, float frequency, float volume)
  46. {
  47. _note_start_us = AP_HAL::micros();
  48. _note_duration_us = duration*1e6;
  49. hal.util->toneAlarm_set_buzzer_tone(frequency, volume, _note_duration_us/1000U);
  50. #if HAL_WITH_UAVCAN
  51. // support CAN buzzers too
  52. uint8_t can_num_drivers = AP::can().get_num_drivers();
  53. for (uint8_t i = 0; i < can_num_drivers; i++) {
  54. AP_UAVCAN *uavcan = AP_UAVCAN::get_uavcan(i);
  55. if (uavcan != nullptr) {
  56. uavcan->set_buzzer_tone(frequency, _note_duration_us*1.0e-6);
  57. }
  58. }
  59. #endif
  60. }
  61. char MMLPlayer::next_char()
  62. {
  63. while (_string[_next] != '\0' && isspace(_string[_next])) {
  64. _next++;
  65. }
  66. return toupper(_string[_next]);
  67. }
  68. uint8_t MMLPlayer::next_number()
  69. {
  70. uint8_t ret = 0;
  71. while (isdigit(next_char())) {
  72. ret = (ret*10) + (next_char() - '0');
  73. _next++;
  74. }
  75. return ret;
  76. }
  77. size_t MMLPlayer::next_dots()
  78. {
  79. size_t ret = 0;
  80. while (next_char() == '.') {
  81. ret++;
  82. _next++;
  83. }
  84. return ret;
  85. }
  86. float MMLPlayer::rest_duration(uint32_t rest_length, uint8_t dots)
  87. {
  88. float whole_note_period = 240.0f / _tempo;
  89. if (rest_length == 0) {
  90. rest_length = 1;
  91. }
  92. float rest_period = whole_note_period/rest_length;
  93. float dot_extension = rest_period/2;
  94. while (dots--) {
  95. rest_period += dot_extension;
  96. dot_extension *= 0.5f;
  97. }
  98. return rest_period;
  99. }
  100. void MMLPlayer::next_action()
  101. {
  102. if (_silence_duration > 0) {
  103. start_silence(_silence_duration);
  104. _silence_duration = 0;
  105. return;
  106. }
  107. uint8_t note = 0;
  108. uint8_t note_length;
  109. while (note == 0) {
  110. char c = next_char();
  111. if (c == '\0') {
  112. if (_repeat) {
  113. play(_string);
  114. } else {
  115. stop();
  116. }
  117. return;
  118. }
  119. _next++;
  120. switch (c) {
  121. case 'V': {
  122. _volume = next_number();
  123. break;
  124. }
  125. case 'L': {
  126. _default_note_length = next_number();
  127. if (_default_note_length == 0) {
  128. stop();
  129. return;
  130. }
  131. break;
  132. }
  133. case 'O':
  134. _octave = next_number();
  135. if (_octave > 6) {
  136. _octave = 6;
  137. }
  138. break;
  139. case '<':
  140. if (_octave > 0) {
  141. _octave--;
  142. }
  143. break;
  144. case '>':
  145. if (_octave < 6) {
  146. _octave++;
  147. }
  148. break;
  149. case 'M':
  150. c = next_char();
  151. if (c == '\0') {
  152. stop();
  153. return;
  154. }
  155. _next++;
  156. switch (c) {
  157. case 'N':
  158. _note_mode = MODE_NORMAL;
  159. break;
  160. case 'L':
  161. _note_mode = MODE_LEGATO;
  162. break;
  163. case 'S':
  164. _note_mode = MODE_STACCATO;
  165. break;
  166. case 'F':
  167. _repeat = false;
  168. break;
  169. case 'B':
  170. _repeat = true;
  171. break;
  172. default:
  173. stop();
  174. return;
  175. }
  176. break;
  177. case 'R':
  178. case 'P': {
  179. uint8_t num = next_number();
  180. uint8_t dots = next_dots();
  181. start_silence(rest_duration(num, dots));
  182. return;
  183. }
  184. case 'T':
  185. _tempo = next_number();
  186. if (_tempo < 32) {
  187. stop();
  188. return;
  189. }
  190. break;
  191. case 'N':
  192. note = next_number();
  193. note_length = _default_note_length;
  194. if (note > 84) {
  195. stop();
  196. return;
  197. }
  198. if (note == 0) {
  199. uint8_t num = next_number();
  200. uint8_t dots = next_dots();
  201. start_silence(rest_duration(num, dots));
  202. return;
  203. }
  204. break;
  205. case 'A':
  206. case 'B':
  207. case 'C':
  208. case 'D':
  209. case 'E':
  210. case 'F':
  211. case 'G': {
  212. static const uint8_t note_tab[] = {9,11,0,2,4,5,7};
  213. note = note_tab[c-'A'] + (_octave*12) + 1;
  214. c = next_char();
  215. switch (c) {
  216. case '#':
  217. case '+':
  218. if (note < 84) {
  219. note++;
  220. }
  221. _next++;
  222. break;
  223. case '-':
  224. if (note > 1) {
  225. note--;
  226. }
  227. _next++;
  228. break;
  229. default:
  230. break;
  231. }
  232. note_length = next_number();
  233. if (note_length == 0) {
  234. note_length = _default_note_length;
  235. }
  236. break;
  237. }
  238. default:
  239. stop();
  240. return;
  241. }
  242. }
  243. // Avoid division by zero
  244. if (_tempo == 0 || note_length == 0) {
  245. stop();
  246. return;
  247. }
  248. float note_period = 240.0f / (float)_tempo / (float)note_length;
  249. switch (_note_mode) {
  250. case MODE_NORMAL:
  251. _silence_duration = note_period/8;
  252. break;
  253. case MODE_STACCATO:
  254. _silence_duration = note_period/4;
  255. break;
  256. case MODE_LEGATO:
  257. _silence_duration = 0;
  258. break;
  259. }
  260. note_period -= _silence_duration;
  261. float dot_extension = note_period/2;
  262. uint8_t dots = next_dots();
  263. while (dots--) {
  264. note_period += dot_extension;
  265. dot_extension *= 0.5f;
  266. }
  267. float note_frequency = 880.0f * expf(logf(2.0f) * ((int)note - 46) / 12.0f);
  268. float note_volume = _volume/255.0f;
  269. note_volume *= AP::notify().get_buzz_volume() * 0.01;
  270. note_volume = constrain_float(note_volume, 0, 1);
  271. note_frequency = constrain_float(note_frequency, 10, 22000);
  272. start_note(note_period, note_frequency, note_volume);
  273. }