mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 03:49:12 +08:00
tone_alarm move to uORB::Subscription
This commit is contained in:
@@ -75,19 +75,10 @@ int ToneAlarm::init()
|
|||||||
void ToneAlarm::next_note()
|
void ToneAlarm::next_note()
|
||||||
{
|
{
|
||||||
if (!_should_run) {
|
if (!_should_run) {
|
||||||
if (_tune_control_sub >= 0) {
|
|
||||||
orb_unsubscribe(_tune_control_sub);
|
|
||||||
}
|
|
||||||
|
|
||||||
_running = false;
|
_running = false;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Subscribe to tune_control.
|
|
||||||
if (_tune_control_sub < 0) {
|
|
||||||
_tune_control_sub = orb_subscribe(ORB_ID(tune_control));
|
|
||||||
}
|
|
||||||
|
|
||||||
// Check for updates
|
// Check for updates
|
||||||
orb_update();
|
orb_update();
|
||||||
|
|
||||||
@@ -136,11 +127,8 @@ void ToneAlarm::Run()
|
|||||||
void ToneAlarm::orb_update()
|
void ToneAlarm::orb_update()
|
||||||
{
|
{
|
||||||
// Check for updates
|
// Check for updates
|
||||||
bool updated = false;
|
if (_tune_control_sub.updated()) {
|
||||||
orb_check(_tune_control_sub, &updated);
|
_tune_control_sub.copy(&_tune);
|
||||||
|
|
||||||
if (updated) {
|
|
||||||
orb_copy(ORB_ID(tune_control), _tune_control_sub, &_tune);
|
|
||||||
|
|
||||||
if (_tune.timestamp > 0) {
|
if (_tune.timestamp > 0) {
|
||||||
_play_tone = _tunes.set_control(_tune) == 0;
|
_play_tone = _tunes.set_control(_tune) == 0;
|
||||||
|
|||||||
@@ -47,8 +47,10 @@
|
|||||||
#include <lib/tunes/tunes.h>
|
#include <lib/tunes/tunes.h>
|
||||||
#include <px4_defines.h>
|
#include <px4_defines.h>
|
||||||
#include <px4_work_queue/ScheduledWorkItem.hpp>
|
#include <px4_work_queue/ScheduledWorkItem.hpp>
|
||||||
#include <string.h>
|
#include <uORB/Subscription.hpp>
|
||||||
|
#include <uORB/topics/tune_control.h>
|
||||||
|
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
#if !defined(UNUSED)
|
#if !defined(UNUSED)
|
||||||
# define UNUSED(a) ((void)(a))
|
# define UNUSED(a) ((void)(a))
|
||||||
@@ -109,7 +111,7 @@ private:
|
|||||||
|
|
||||||
unsigned int _silence_length{0}; ///< If nonzero, silence before next note.
|
unsigned int _silence_length{0}; ///< If nonzero, silence before next note.
|
||||||
|
|
||||||
int _tune_control_sub{-1};
|
uORB::Subscription _tune_control_sub{ORB_ID(tune_control)};
|
||||||
|
|
||||||
tune_control_s _tune{};
|
tune_control_s _tune{};
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user