AP_Notify: run astyle on ToneAlarm and MMLPlayer
This commit is contained in:
parent
b31ddedfef
commit
720676b28c
@ -6,14 +6,16 @@
|
|||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
void MMLPlayer::update() {
|
void MMLPlayer::update()
|
||||||
|
{
|
||||||
// Check if note is over
|
// Check if note is over
|
||||||
if (_playing && AP_HAL::micros()-_note_start_us > _note_duration_us) {
|
if (_playing && AP_HAL::micros()-_note_start_us > _note_duration_us) {
|
||||||
next_action();
|
next_action();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void MMLPlayer::play(const char* string) {
|
void MMLPlayer::play(const char* string)
|
||||||
|
{
|
||||||
stop();
|
stop();
|
||||||
|
|
||||||
_string = string;
|
_string = string;
|
||||||
@ -30,24 +32,28 @@ void MMLPlayer::play(const char* string) {
|
|||||||
next_action();
|
next_action();
|
||||||
}
|
}
|
||||||
|
|
||||||
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);
|
||||||
}
|
}
|
||||||
|
|
||||||
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);
|
||||||
}
|
}
|
||||||
|
|
||||||
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);
|
||||||
}
|
}
|
||||||
|
|
||||||
char MMLPlayer::next_char() {
|
char MMLPlayer::next_char()
|
||||||
|
{
|
||||||
while (_string[_next] != '\0' && isspace(_string[_next])) {
|
while (_string[_next] != '\0' && isspace(_string[_next])) {
|
||||||
_next++;
|
_next++;
|
||||||
}
|
}
|
||||||
@ -55,7 +61,8 @@ char MMLPlayer::next_char() {
|
|||||||
return toupper(_string[_next]);
|
return toupper(_string[_next]);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t MMLPlayer::next_number() {
|
uint8_t MMLPlayer::next_number()
|
||||||
|
{
|
||||||
uint8_t ret = 0;
|
uint8_t ret = 0;
|
||||||
while (isdigit(next_char())) {
|
while (isdigit(next_char())) {
|
||||||
ret = (ret*10) + (next_char() - '0');
|
ret = (ret*10) + (next_char() - '0');
|
||||||
@ -64,7 +71,8 @@ uint8_t MMLPlayer::next_number() {
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t MMLPlayer::next_dots() {
|
size_t MMLPlayer::next_dots()
|
||||||
|
{
|
||||||
size_t ret = 0;
|
size_t ret = 0;
|
||||||
while (next_char() == '.') {
|
while (next_char() == '.') {
|
||||||
ret++;
|
ret++;
|
||||||
@ -73,7 +81,8 @@ size_t MMLPlayer::next_dots() {
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
float MMLPlayer::rest_duration(uint32_t rest_length, uint8_t dots) {
|
float MMLPlayer::rest_duration(uint32_t rest_length, uint8_t dots)
|
||||||
|
{
|
||||||
float whole_note_period = 240.0f / _tempo;
|
float whole_note_period = 240.0f / _tempo;
|
||||||
if (rest_length == 0) {
|
if (rest_length == 0) {
|
||||||
rest_length = 1;
|
rest_length = 1;
|
||||||
@ -90,7 +99,8 @@ float MMLPlayer::rest_duration(uint32_t rest_length, uint8_t dots) {
|
|||||||
return rest_period;
|
return rest_period;
|
||||||
}
|
}
|
||||||
|
|
||||||
void MMLPlayer::next_action() {
|
void MMLPlayer::next_action()
|
||||||
|
{
|
||||||
if (_silence_duration > 0) {
|
if (_silence_duration > 0) {
|
||||||
start_silence(_silence_duration);
|
start_silence(_silence_duration);
|
||||||
_silence_duration = 0;
|
_silence_duration = 0;
|
||||||
|
@ -129,7 +129,8 @@ void ToneAlarm::play_tone(const uint8_t tone_index)
|
|||||||
play_string(tone_requested.str);
|
play_string(tone_requested.str);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ToneAlarm::_timer_task() {
|
void ToneAlarm::_timer_task()
|
||||||
|
{
|
||||||
if (_sem) {
|
if (_sem) {
|
||||||
_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER);
|
_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER);
|
||||||
_mml_player.update();
|
_mml_player.update();
|
||||||
@ -137,7 +138,8 @@ void ToneAlarm::_timer_task() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ToneAlarm::play_string(const char *str) {
|
void ToneAlarm::play_string(const char *str)
|
||||||
|
{
|
||||||
if (_sem) {
|
if (_sem) {
|
||||||
_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER);
|
_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER);
|
||||||
_mml_player.stop();
|
_mml_player.stop();
|
||||||
@ -148,7 +150,8 @@ void ToneAlarm::play_string(const char *str) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ToneAlarm::stop_cont_tone() {
|
void ToneAlarm::stop_cont_tone()
|
||||||
|
{
|
||||||
if (_cont_tone_playing == _tone_playing) {
|
if (_cont_tone_playing == _tone_playing) {
|
||||||
play_string("");
|
play_string("");
|
||||||
_tone_playing = -1;
|
_tone_playing = -1;
|
||||||
@ -156,7 +159,8 @@ void ToneAlarm::stop_cont_tone() {
|
|||||||
_cont_tone_playing = -1;
|
_cont_tone_playing = -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ToneAlarm::check_cont_tone() {
|
void ToneAlarm::check_cont_tone()
|
||||||
|
{
|
||||||
uint32_t tnow_ms = AP_HAL::millis();
|
uint32_t tnow_ms = AP_HAL::millis();
|
||||||
// if we are supposed to be playing a continuous tone,
|
// if we are supposed to be playing a continuous tone,
|
||||||
// and it was interrupted, and the interrupting tone has timed out,
|
// and it was interrupted, and the interrupting tone has timed out,
|
||||||
|
@ -24,8 +24,7 @@
|
|||||||
#define AP_NOTIFY_PX4_MAX_TONE_LENGTH_MS 2000
|
#define AP_NOTIFY_PX4_MAX_TONE_LENGTH_MS 2000
|
||||||
#define AP_NOTIFY_TONEALARM_TONE_BUF_SIZE 512
|
#define AP_NOTIFY_TONEALARM_TONE_BUF_SIZE 512
|
||||||
|
|
||||||
class ToneAlarm: public NotifyDevice
|
class ToneAlarm: public NotifyDevice {
|
||||||
{
|
|
||||||
public:
|
public:
|
||||||
/// init - initialised the tone alarm
|
/// init - initialised the tone alarm
|
||||||
bool init(void);
|
bool init(void);
|
||||||
|
Loading…
Reference in New Issue
Block a user