NotifyDevice.h 809 B

12345678910111213141516171819202122232425262728
  1. #pragma once
  2. #include <AP_Common/AP_Common.h>
  3. #include <GCS_MAVLink/GCS_MAVLink.h>
  4. class AP_Notify;
  5. class NotifyDevice {
  6. public:
  7. virtual ~NotifyDevice() {}
  8. // init - initialised the device
  9. virtual bool init(void) = 0;
  10. // update - updates device according to timed_updated. Should be
  11. // called at 50Hz
  12. virtual void update() = 0;
  13. // handle a LED_CONTROL message, by default device ignore message
  14. virtual void handle_led_control(const mavlink_message_t &msg) {}
  15. // handle a PLAY_TUNE message, by default device ignore message
  16. virtual void handle_play_tune(const mavlink_message_t &msg) {}
  17. // play a MML tune
  18. virtual void play_tune(const char *tune) {}
  19. // this pointer is used to read the parameters relative to devices
  20. const AP_Notify *pNotify;
  21. };