1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465 |
- #pragma once
- #include <AP_Param/AP_Param.h>
- #include <AP_Relay/AP_Relay.h>
- class AP_ServoRelayEvents {
- public:
- AP_ServoRelayEvents()
- : type(EVENT_TYPE_RELAY)
- {
- _singleton = this;
- }
-
- AP_ServoRelayEvents(const AP_ServoRelayEvents &other) = delete;
- AP_ServoRelayEvents &operator=(const AP_ServoRelayEvents&) = delete;
-
- static AP_ServoRelayEvents *get_singleton() {
- return _singleton;
- }
- bool do_set_servo(uint8_t channel, uint16_t pwm);
- bool do_set_relay(uint8_t relay_num, uint8_t state);
- bool do_repeat_servo(uint8_t channel, uint16_t servo_value, int16_t repeat, uint16_t delay_time_ms);
- bool do_repeat_relay(uint8_t relay_num, int16_t count, uint32_t period_ms);
- void update_events(void);
- private:
- static AP_ServoRelayEvents *_singleton;
-
- enum event_type {
- EVENT_TYPE_RELAY=0,
- EVENT_TYPE_SERVO=1
- };
- enum event_type type;
-
- uint32_t start_time_ms;
-
- uint16_t delay_ms;
-
- int16_t repeat;
-
- uint8_t channel;
-
- uint16_t servo_value;
- };
- namespace AP {
- AP_ServoRelayEvents *servorelayevents();
- };
|