APM:Libraries
AP_ServoRelayEvents.h
Go to the documentation of this file.
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 
9 #include <AP_Param/AP_Param.h>
10 #include <AP_Relay/AP_Relay.h>
11 
13 public:
15  : relay(_relay)
17  {
18  _singleton = this;
19  }
20 
21  /* Do not allow copies */
22  AP_ServoRelayEvents(const AP_ServoRelayEvents &other) = delete;
24 
25  // get singleton instance
27  return _singleton;
28  }
29 
30  // set allowed servo channel mask
31  void set_channel_mask(uint16_t _mask) { mask = _mask; }
32 
33  bool do_set_servo(uint8_t channel, uint16_t pwm);
34  bool do_set_relay(uint8_t relay_num, uint8_t state);
35  bool do_repeat_servo(uint8_t channel, uint16_t servo_value, int16_t repeat, uint16_t delay_time_ms);
36  bool do_repeat_relay(uint8_t relay_num, int16_t count, uint32_t period_ms);
37  void update_events(void);
38 
39 private:
40 
42 
44  uint16_t mask;
45 
46  // event control state
47  enum event_type {
50  };
51 
53 
54  // when the event was started in ms
55  uint32_t start_time_ms;
56 
57  // how long to delay the next firing of event in millis
58  uint16_t delay_ms;
59 
60  // how many times to cycle : -1 (or -2) = forever, 2 = do one cycle, 4 = do two cycles
61  int16_t repeat;
62 
63  // RC channel for servos, relay number for relays
64  uint8_t channel;
65 
66  // PWM for servos
67  uint16_t servo_value;
68 };
69 
70 namespace AP {
72 };
bool do_repeat_servo(uint8_t channel, uint16_t servo_value, int16_t repeat, uint16_t delay_time_ms)
AP_ServoRelayEvents & operator=(const AP_ServoRelayEvents &)=delete
AP_ServoRelayEvents * servorelayevents()
AP_ServoRelayEvents(AP_Relay &_relay)
void set_channel_mask(uint16_t _mask)
bool do_set_servo(uint8_t channel, uint16_t pwm)
bool do_repeat_relay(uint8_t relay_num, int16_t count, uint32_t period_ms)
static uint16_t pwm
Definition: RCOutput.cpp:20
A system for managing and storing variables that are of general interest to the system.
Definition: AP_AHRS.cpp:486
static AP_ServoRelayEvents * get_singleton()
static int state
Definition: Util.cpp:20
static AP_ServoRelayEvents * _singleton
Class to manage the ArduPilot relay.
Definition: AP_Relay.h:18
bool do_set_relay(uint8_t relay_num, uint8_t state)
APM relay control class.