Buzzer.cpp 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159
  1. /*
  2. Buzzer driver
  3. */
  4. /*
  5. This program is free software: you can redistribute it and/or modify
  6. it under the terms of the GNU General Public License as published by
  7. the Free Software Foundation, either version 3 of the License, or
  8. (at your option) any later version.
  9. This program is distributed in the hope that it will be useful,
  10. but WITHOUT ANY WARRANTY; without even the implied warranty of
  11. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  12. GNU General Public License for more details.
  13. You should have received a copy of the GNU General Public License
  14. along with this program. If not, see <http://www.gnu.org/licenses/>.
  15. */
  16. #include "Buzzer.h"
  17. #include <AP_HAL/AP_HAL.h>
  18. #include "AP_Notify.h"
  19. #ifndef HAL_BUZZER_ON
  20. #if !defined(HAL_BUZZER_PIN)
  21. #define HAL_BUZZER_ON (pNotify->get_buzz_level())
  22. #define HAL_BUZZER_OFF (!pNotify->get_buzz_level())
  23. #else
  24. #define HAL_BUZZER_ON 1
  25. #define HAL_BUZZER_OFF 0
  26. #endif
  27. #endif
  28. extern const AP_HAL::HAL& hal;
  29. bool Buzzer::init()
  30. {
  31. if (pNotify->buzzer_enabled() == false) {
  32. return false;
  33. }
  34. #if defined(HAL_BUZZER_PIN)
  35. _pin = HAL_BUZZER_PIN;
  36. #else
  37. _pin = pNotify->get_buzz_pin();
  38. #endif
  39. if(!_pin) return false;
  40. // setup the pin and ensure it's off
  41. hal.gpio->pinMode(_pin, HAL_GPIO_OUTPUT);
  42. on(false);
  43. // set initial boot states. This prevents us issuing a arming
  44. // warning in plane and rover on every boot
  45. _flags.armed = AP_Notify::flags.armed;
  46. _flags.failsafe_battery = AP_Notify::flags.failsafe_battery;
  47. return true;
  48. }
  49. // update - updates led according to timed_updated. Should be called at 50Hz
  50. void Buzzer::update()
  51. {
  52. update_pattern_to_play();
  53. update_playing_pattern();
  54. }
  55. void Buzzer::update_pattern_to_play()
  56. {
  57. // check for arming failed event
  58. if (AP_Notify::events.arming_failed) {
  59. // arming failed buzz
  60. play_pattern(SINGLE_BUZZ);
  61. return;
  62. }
  63. if (AP_HAL::millis() - _pattern_start_time < _pattern_start_interval_time_ms) {
  64. // do not interrupt playing patterns / enforce minumum separation
  65. return;
  66. }
  67. // check if armed status has changed
  68. if (_flags.armed != AP_Notify::flags.armed) {
  69. _flags.armed = AP_Notify::flags.armed;
  70. if (_flags.armed) {
  71. // double buzz when armed
  72. play_pattern(ARMING_BUZZ);
  73. }else{
  74. // single buzz when disarmed
  75. play_pattern(SINGLE_BUZZ);
  76. }
  77. return;
  78. }
  79. // check ekf bad
  80. if (_flags.ekf_bad != AP_Notify::flags.ekf_bad) {
  81. _flags.ekf_bad = AP_Notify::flags.ekf_bad;
  82. if (_flags.ekf_bad) {
  83. // ekf bad warning buzz
  84. play_pattern(EKF_BAD);
  85. }
  86. return;
  87. }
  88. // if vehicle lost was enabled, starting beep
  89. if (AP_Notify::flags.vehicle_lost) {
  90. play_pattern(DOUBLE_BUZZ);
  91. return;
  92. }
  93. // if battery failsafe constantly single buzz
  94. if (AP_Notify::flags.failsafe_battery) {
  95. play_pattern(SINGLE_BUZZ);
  96. return;
  97. }
  98. }
  99. void Buzzer::update_playing_pattern()
  100. {
  101. if (_pattern == 0UL) {
  102. return;
  103. }
  104. const uint32_t now = AP_HAL::millis();
  105. const uint32_t delta = now - _pattern_start_time;
  106. if (delta >= 3200) {
  107. // finished playing pattern
  108. on(false);
  109. _pattern = 0UL;
  110. return;
  111. }
  112. const uint32_t bit = delta / 100UL; // each bit is 100ms
  113. on(_pattern & (1U<<(31-bit)));
  114. }
  115. // on - turns the buzzer on or off
  116. void Buzzer::on(bool turn_on)
  117. {
  118. // return immediately if nothing to do
  119. if (_flags.on == turn_on) {
  120. return;
  121. }
  122. // update state
  123. _flags.on = turn_on;
  124. // pull pin high or low
  125. hal.gpio->write(_pin, _flags.on? HAL_BUZZER_ON : HAL_BUZZER_OFF);
  126. }
  127. /// play_pattern - plays the defined buzzer pattern
  128. void Buzzer::play_pattern(const uint32_t pattern)
  129. {
  130. _pattern = pattern;
  131. _pattern_start_time = AP_HAL::millis();
  132. }