|
|
|
@ -18,6 +18,7 @@
@@ -18,6 +18,7 @@
|
|
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h> |
|
|
|
|
#include <AP_Math/AP_Math.h> |
|
|
|
|
#include <AP_Common/Semaphore.h> |
|
|
|
|
|
|
|
|
|
#include "ToneAlarm.h" |
|
|
|
|
#include "AP_Notify.h" |
|
|
|
@ -100,8 +101,6 @@ bool AP_ToneAlarm::init()
@@ -100,8 +101,6 @@ bool AP_ToneAlarm::init()
|
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_sem = hal.util->new_semaphore(); |
|
|
|
|
|
|
|
|
|
// set initial boot states. This prevents us issuing a arming
|
|
|
|
|
// warning in plane and rover on every boot
|
|
|
|
|
flags.armed = AP_Notify::flags.armed; |
|
|
|
@ -131,21 +130,18 @@ void AP_ToneAlarm::play_tone(const uint8_t tone_index)
@@ -131,21 +130,18 @@ void AP_ToneAlarm::play_tone(const uint8_t tone_index)
|
|
|
|
|
|
|
|
|
|
void AP_ToneAlarm::_timer_task() |
|
|
|
|
{ |
|
|
|
|
if (_sem && _sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { |
|
|
|
|
WITH_SEMAPHORE(_sem); |
|
|
|
|
_mml_player.update(); |
|
|
|
|
_sem->give(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void AP_ToneAlarm::play_string(const char *str) |
|
|
|
|
{ |
|
|
|
|
if (_sem && _sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { |
|
|
|
|
WITH_SEMAPHORE(_sem); |
|
|
|
|
|
|
|
|
|
_mml_player.stop(); |
|
|
|
|
strncpy(_tone_buf, str, AP_NOTIFY_TONEALARM_TONE_BUF_SIZE); |
|
|
|
|
_tone_buf[AP_NOTIFY_TONEALARM_TONE_BUF_SIZE-1] = 0; |
|
|
|
|
_mml_player.play(_tone_buf); |
|
|
|
|
_sem->give(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void AP_ToneAlarm::stop_cont_tone() |
|
|
|
@ -390,7 +386,8 @@ void AP_ToneAlarm::handle_play_tune(mavlink_message_t *msg)
@@ -390,7 +386,8 @@ void AP_ToneAlarm::handle_play_tune(mavlink_message_t *msg)
|
|
|
|
|
|
|
|
|
|
mavlink_msg_play_tune_decode(msg, &packet); |
|
|
|
|
|
|
|
|
|
if (_sem && _sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { |
|
|
|
|
WITH_SEMAPHORE(_sem); |
|
|
|
|
|
|
|
|
|
_mml_player.stop(); |
|
|
|
|
|
|
|
|
|
strncpy(_tone_buf, packet.tune, MIN(sizeof(packet.tune), sizeof(_tone_buf)-1)); |
|
|
|
@ -401,6 +398,4 @@ void AP_ToneAlarm::handle_play_tune(mavlink_message_t *msg)
@@ -401,6 +398,4 @@ void AP_ToneAlarm::handle_play_tune(mavlink_message_t *msg)
|
|
|
|
|
strncpy(_tone_buf+len, packet.tune2, len2); |
|
|
|
|
_tone_buf[sizeof(_tone_buf)-1] = 0; |
|
|
|
|
_mml_player.play(_tone_buf); |
|
|
|
|
_sem->give(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|