mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: added duration to toneAlarm_set_buzzer_tone
This commit is contained in:
parent
949324ff2b
commit
c83567dcba
|
@ -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 {
|
||||
|
|
|
@ -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…
Reference in New Issue