RSeries astromech firmware
ServoDecoder.h
Go to the documentation of this file.
1 #ifndef ServoDecoder_h
2 #define ServoDecoder_h
3 
4 #include "ReelTwo.h"
5 #include "core/SetupEvent.h"
6 #include "core/AnimatedEvent.h"
7 
9 {
10 public:
11  ServoDecoder(void (*changeNotify)(int pin, uint16_t pwm), byte pin) :
12  fPin(pin),
13  fChangeNotify(changeNotify)
14  {
15  pinMode(pin, INPUT_PULLUP);
16  Private* _priv = priv();
17  fISR = _priv->fISRCount++;
18 
19  _priv->fISRPin[fISR] = pin;
20 // Should be INPUT_PULLUP
21 // pinMode(_priv->fISRPin[fISR], INPUT);
22  }
23 
24  virtual void setup() override
25  {
26  begin(true);
27  }
28 
29  virtual void animate() override
30  {
31  int32_t val = getValue();
32  if (hasChanged())
33  {
34  if (fChangeNotify != NULL)
35  fChangeNotify(fPin, val);
36  fValue = val;
37  }
38  fAliveStateChange = false;
39  if (isActive())
40  {
41  if (!fAlive)
42  {
43  fAlive = true;
44  fAliveStateChange = true;
45  }
46  }
47  else if (fAlive)
48  {
49  fAlive = false;
50  fAliveStateChange = true;
51  }
52  }
53 
54  bool begin(bool measurePulseHigh = true)
55  {
56  Private* _priv = priv();
57  uint8_t pin = _priv->fISRPin[fISR];
58  _priv->fISRLastState[fISR] = digitalRead(pin);
59  _priv->fISRTriggerState[fISR] = measurePulseHigh;
60  uint8_t inum = digitalPinToInterrupt(pin);
61  switch (fISR) {
62  #define ATTACH_INTTERUPT(num) \
63  case num: \
64  attachInterrupt(inum, ISR_##num, CHANGE); \
65  break;
86 
87  #undef ATTACH_INTTERUPT
88  default:
89  return false;
90  }
91  return true;
92  }
93 
94  inline bool hasChanged()
95  {
96  unsigned int val = getValue();
97  int32_t curval = fValue;
98  return (!(val >= curval-10 && val <= curval+10));
99  }
100 
101 
102  unsigned int getValue()
103  {
104  Private* _priv = priv();
105  noInterrupts();
106  unsigned int val = _priv->fISRValue[fISR];
107  interrupts();
108  return val;
109  }
110 
111  unsigned long getAge()
112  {
113  Private* _priv = priv();
114  noInterrupts();
115  unsigned int age = millis() - _priv->fISRMillis[fISR];
116  interrupts();
117  return age;
118  }
119 
120  bool isActive()
121  {
122  return (fValue != 0 && getAge() < 250);
123  }
124 
126  {
127  return (fAliveStateChange && fAlive);
128  }
129 
131  {
132  return (fAliveStateChange && !fAlive);
133  }
134 
135  void end()
136  {
137  Private* _priv = priv();
138  detachInterrupt(digitalPinToInterrupt(_priv->fISRPin[fISR]));
139  }
140 
141 private:
142  static constexpr byte MAX_ISR_COUNT = 20;
143  struct Private
144  {
145  byte fISRCount;
146  byte fISRPin[MAX_ISR_COUNT];
147  unsigned int fISRValue[MAX_ISR_COUNT];
148  bool fISRLastState[MAX_ISR_COUNT];
149  bool fISRTriggerState[MAX_ISR_COUNT];
150  unsigned long fISRMillis[MAX_ISR_COUNT];
151  unsigned long fISRTimer[MAX_ISR_COUNT];
152  unsigned long fISRAge[MAX_ISR_COUNT];
153  };
154  uint8_t fPin;
155  byte fISR;
156  uint16_t fValue;
157  bool fAlive = false;
158  bool fAliveStateChange = false;
159  void (*fChangeNotify)(int pin, uint16_t pwm);
160 
161  static Private* priv()
162  {
163  static Private _priv;
164  return &_priv;
165  }
166 
167  static void ISR_generic(byte isr)
168  {
169  Private* _priv = priv();
170  unsigned long now = micros();
171  bool state_now = digitalRead(_priv->fISRPin[isr]);
172  if (state_now != _priv->fISRLastState[isr])
173  {
174  if (state_now == _priv->fISRTriggerState[isr])
175  {
176  _priv->fISRTimer[isr] = now;
177  }
178  else
179  {
180  uint16_t pulseGap = (unsigned int)(now - _priv->fISRTimer[isr]);
181  if (pulseGap > 850 && pulseGap < 2150)
182  {
183  _priv->fISRValue[isr] = pulseGap;
184  _priv->fISRMillis[isr] = millis();
185  }
186  _priv->fISRAge[isr] = now;
187  }
188  _priv->fISRLastState[isr] = state_now;
189  }
190  }
191 
192  #define DEFINE_ISR_HANDLER(n) \
193  static void ISR_##n() \
194  { \
195  ISR_generic(n); \
196  }
197 
218 
219  #undef DEFINE_ISR_HANDLER
220 };
221 
222 #endif
ATTACH_INTTERUPT
#define ATTACH_INTTERUPT(num)
ServoDecoder::end
void end()
Definition: ServoDecoder.h:135
ReelTwo.h
SetupEvent.h
AnimatedEvent
Base class for all animated devices. AnimatedEvent::animate() is called for each device once through ...
Definition: AnimatedEvent.h:18
SetupEvent
Base class for all devices that require setup that cannot happen in the constructor....
Definition: SetupEvent.h:15
ServoDecoder::getValue
unsigned int getValue()
Definition: ServoDecoder.h:102
ServoDecoder::hasChanged
bool hasChanged()
Definition: ServoDecoder.h:94
AnimatedEvent.h
ServoDecoder::getAge
unsigned long getAge()
Definition: ServoDecoder.h:111
ServoDecoder::ServoDecoder
ServoDecoder(void(*changeNotify)(int pin, uint16_t pwm), byte pin)
Definition: ServoDecoder.h:11
MAX_ISR_COUNT
#define MAX_ISR_COUNT
Definition: PinInterruptHandler.h:90
ServoDecoder::setup
virtual void setup() override
Subclasses must implement this function to perform any necessary setup that cannot happen in the cons...
Definition: ServoDecoder.h:24
ServoDecoder::becameActive
bool becameActive()
Definition: ServoDecoder.h:125
ServoDecoder::animate
virtual void animate() override
Subclasses must implement this function to run through a single frame of animation/activity.
Definition: ServoDecoder.h:29
ServoDecoder::isActive
bool isActive()
Definition: ServoDecoder.h:120
ServoDecoder
Definition: ServoDecoder.h:8
DEFINE_ISR_HANDLER
#define DEFINE_ISR_HANDLER(n)
Definition: ServoDecoder.h:192
ServoDecoder::begin
bool begin(bool measurePulseHigh=true)
Definition: ServoDecoder.h:54
ServoDecoder::becameInactive
bool becameInactive()
Definition: ServoDecoder.h:130