AP_ServoRelayEvents.h 1.5 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465
  1. /*
  2. * AP_ServoRelayEvent.h
  3. *
  4. * handle DO_SET_SERVO, DO_REPEAT_SERVO, DO_SET_RELAY and
  5. * DO_REPEAT_RELAY commands
  6. */
  7. #pragma once
  8. #include <AP_Param/AP_Param.h>
  9. #include <AP_Relay/AP_Relay.h>
  10. class AP_ServoRelayEvents {
  11. public:
  12. AP_ServoRelayEvents()
  13. : type(EVENT_TYPE_RELAY)
  14. {
  15. _singleton = this;
  16. }
  17. /* Do not allow copies */
  18. AP_ServoRelayEvents(const AP_ServoRelayEvents &other) = delete;
  19. AP_ServoRelayEvents &operator=(const AP_ServoRelayEvents&) = delete;
  20. // get singleton instance
  21. static AP_ServoRelayEvents *get_singleton() {
  22. return _singleton;
  23. }
  24. bool do_set_servo(uint8_t channel, uint16_t pwm);
  25. bool do_set_relay(uint8_t relay_num, uint8_t state);
  26. bool do_repeat_servo(uint8_t channel, uint16_t servo_value, int16_t repeat, uint16_t delay_time_ms);
  27. bool do_repeat_relay(uint8_t relay_num, int16_t count, uint32_t period_ms);
  28. void update_events(void);
  29. private:
  30. static AP_ServoRelayEvents *_singleton;
  31. // event control state
  32. enum event_type {
  33. EVENT_TYPE_RELAY=0,
  34. EVENT_TYPE_SERVO=1
  35. };
  36. enum event_type type;
  37. // when the event was started in ms
  38. uint32_t start_time_ms;
  39. // how long to delay the next firing of event in millis
  40. uint16_t delay_ms;
  41. // how many times to cycle : -1 (or -2) = forever, 2 = do one cycle, 4 = do two cycles
  42. int16_t repeat;
  43. // RC channel for servos, relay number for relays
  44. uint8_t channel;
  45. // PWM for servos
  46. uint16_t servo_value;
  47. };
  48. namespace AP {
  49. AP_ServoRelayEvents *servorelayevents();
  50. };