|
|
|
@ -13,20 +13,20 @@ class AP_ServoRelayEvents {
@@ -13,20 +13,20 @@ class AP_ServoRelayEvents {
|
|
|
|
|
public: |
|
|
|
|
AP_ServoRelayEvents(AP_Relay &_relay) |
|
|
|
|
: relay(_relay) |
|
|
|
|
, mask(0) |
|
|
|
|
, type(EVENT_TYPE_RELAY) |
|
|
|
|
, start_time_ms(0) |
|
|
|
|
, delay_ms(0) |
|
|
|
|
, repeat(0) |
|
|
|
|
, channel(0) |
|
|
|
|
, servo_value(0) |
|
|
|
|
{ |
|
|
|
|
_singleton = this; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* Do not allow copies */ |
|
|
|
|
AP_ServoRelayEvents(const AP_ServoRelayEvents &other) = delete; |
|
|
|
|
AP_ServoRelayEvents &operator=(const AP_ServoRelayEvents&) = delete; |
|
|
|
|
|
|
|
|
|
// get singleton instance
|
|
|
|
|
static AP_ServoRelayEvents *get_singleton() { |
|
|
|
|
return _singleton; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// set allowed servo channel mask
|
|
|
|
|
void set_channel_mask(uint16_t _mask) { mask = _mask; } |
|
|
|
|
|
|
|
|
@ -37,6 +37,9 @@ public:
@@ -37,6 +37,9 @@ public:
|
|
|
|
|
void update_events(void); |
|
|
|
|
|
|
|
|
|
private: |
|
|
|
|
|
|
|
|
|
static AP_ServoRelayEvents *_singleton; |
|
|
|
|
|
|
|
|
|
AP_Relay &relay; |
|
|
|
|
uint16_t mask; |
|
|
|
|
|
|
|
|
@ -63,3 +66,7 @@ private:
@@ -63,3 +66,7 @@ private:
|
|
|
|
|
// PWM for servos
|
|
|
|
|
uint16_t servo_value; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
namespace AP { |
|
|
|
|
AP_ServoRelayEvents *servorelayevents(); |
|
|
|
|
}; |
|
|
|
|