mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_Notify: added duration to toneAlarm_set_buzzer_tone
This commit is contained in:
parent
22d588146e
commit
d28c8f0214
@ -36,21 +36,21 @@ void MMLPlayer::play(const char* string)
|
|||||||
void MMLPlayer::stop()
|
void MMLPlayer::stop()
|
||||||
{
|
{
|
||||||
_playing = false;
|
_playing = false;
|
||||||
hal.util->toneAlarm_set_buzzer_tone(0,0);
|
hal.util->toneAlarm_set_buzzer_tone(0,0,0);
|
||||||
}
|
}
|
||||||
|
|
||||||
void MMLPlayer::start_silence(float duration)
|
void MMLPlayer::start_silence(float duration)
|
||||||
{
|
{
|
||||||
_note_start_us = AP_HAL::micros();
|
_note_start_us = AP_HAL::micros();
|
||||||
_note_duration_us = duration*1e6;
|
_note_duration_us = duration*1e6;
|
||||||
hal.util->toneAlarm_set_buzzer_tone(0, 0);
|
hal.util->toneAlarm_set_buzzer_tone(0, 0, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
void MMLPlayer::start_note(float duration, float frequency, float volume)
|
void MMLPlayer::start_note(float duration, float frequency, float volume)
|
||||||
{
|
{
|
||||||
_note_start_us = AP_HAL::micros();
|
_note_start_us = AP_HAL::micros();
|
||||||
_note_duration_us = duration*1e6;
|
_note_duration_us = duration*1e6;
|
||||||
hal.util->toneAlarm_set_buzzer_tone(frequency, volume);
|
hal.util->toneAlarm_set_buzzer_tone(frequency, volume, _note_duration_us/1000U);
|
||||||
}
|
}
|
||||||
|
|
||||||
char MMLPlayer::next_char()
|
char MMLPlayer::next_char()
|
||||||
|
Loading…
Reference in New Issue
Block a user