2016-02-17 21:25:41 -04:00
|
|
|
#pragma once
|
2014-11-14 10:14:40 -04:00
|
|
|
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
2015-02-26 03:07:33 -04:00
|
|
|
|
2015-12-01 16:22:26 -04:00
|
|
|
class AP_Notify;
|
|
|
|
|
2014-11-14 10:14:40 -04:00
|
|
|
class NotifyDevice {
|
|
|
|
public:
|
|
|
|
virtual ~NotifyDevice() {}
|
|
|
|
// init - initialised the device
|
|
|
|
virtual bool init(void) = 0;
|
|
|
|
// update - updates device according to timed_updated. Should be
|
|
|
|
// called at 50Hz
|
|
|
|
virtual void update() = 0;
|
2016-07-22 00:37:25 -03:00
|
|
|
|
2015-02-26 03:07:33 -04:00
|
|
|
// handle a LED_CONTROL message, by default device ignore message
|
|
|
|
virtual void handle_led_control(mavlink_message_t *msg) {}
|
2015-12-01 16:22:26 -04:00
|
|
|
|
2016-07-22 00:37:25 -03:00
|
|
|
// handle a PLAY_TUNE message, by default device ignore message
|
|
|
|
virtual void handle_play_tune(mavlink_message_t *msg) {}
|
2019-03-18 23:35:15 -03:00
|
|
|
|
|
|
|
// play a MML tune
|
|
|
|
virtual void play_tune(const char *tune) {}
|
2016-07-22 00:37:25 -03:00
|
|
|
|
2015-12-01 16:22:26 -04:00
|
|
|
// this pointer is used to read the parameters relative to devices
|
|
|
|
const AP_Notify *pNotify;
|
2014-11-14 10:14:40 -04:00
|
|
|
};
|