mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
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;
|
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)) {
|
if (is_zero(frequency) || is_zero(volume)) {
|
||||||
pwmDisableChannel(_toneAlarm_pwm_group.pwm_drv, _toneAlarm_pwm_group.chan);
|
pwmDisableChannel(_toneAlarm_pwm_group.pwm_drv, _toneAlarm_pwm_group.chan);
|
||||||
} else {
|
} else {
|
||||||
|
@ -48,7 +48,7 @@ public:
|
|||||||
|
|
||||||
#ifdef HAL_PWM_ALARM
|
#ifdef HAL_PWM_ALARM
|
||||||
bool toneAlarm_init() override;
|
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
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
Loading…
Reference in New Issue
Block a user