Browse Source

HAL_ChibiOS: added duration to toneAlarm_set_buzzer_tone

mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
c83567dcba
  1. 3
      libraries/AP_HAL_ChibiOS/Util.cpp
  2. 2
      libraries/AP_HAL_ChibiOS/Util.h

3
libraries/AP_HAL_ChibiOS/Util.cpp

@ -153,7 +153,8 @@ bool Util::toneAlarm_init() @@ -153,7 +153,8 @@ bool Util::toneAlarm_init()
return true;
}
void Util::toneAlarm_set_buzzer_tone(float frequency, float volume) {
void Util::toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t duration_ms)
{
if (is_zero(frequency) || is_zero(volume)) {
pwmDisableChannel(_toneAlarm_pwm_group.pwm_drv, _toneAlarm_pwm_group.chan);
} else {

2
libraries/AP_HAL_ChibiOS/Util.h

@ -48,7 +48,7 @@ public: @@ -48,7 +48,7 @@ public:
#ifdef HAL_PWM_ALARM
bool toneAlarm_init() override;
void toneAlarm_set_buzzer_tone(float frequency, float volume) override;
void toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t duration_ms) override;
#endif
private:

Loading…
Cancel
Save