11 ServoDecoder(
void (*changeNotify)(
int pin, uint16_t pwm),
byte pin) :
13 fChangeNotify(changeNotify)
15 pinMode(pin, INPUT_PULLUP);
16 Private* _priv = priv();
17 fISR = _priv->fISRCount++;
19 _priv->fISRPin[fISR] = pin;
34 if (fChangeNotify != NULL)
35 fChangeNotify(fPin, val);
38 fAliveStateChange =
false;
44 fAliveStateChange =
true;
50 fAliveStateChange =
true;
54 bool begin(
bool measurePulseHigh =
true)
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);
62 #define ATTACH_INTTERUPT(num) \
64 attachInterrupt(inum, ISR_##num, CHANGE); \
87 #undef ATTACH_INTTERUPT
97 int32_t curval = fValue;
98 return (!(val >= curval-10 && val <= curval+10));
104 Private* _priv = priv();
106 unsigned int val = _priv->fISRValue[fISR];
113 Private* _priv = priv();
115 unsigned int age = millis() - _priv->fISRMillis[fISR];
122 return (fValue != 0 &&
getAge() < 250);
127 return (fAliveStateChange && fAlive);
132 return (fAliveStateChange && !fAlive);
137 Private* _priv = priv();
138 detachInterrupt(digitalPinToInterrupt(_priv->fISRPin[fISR]));
142 static constexpr
byte MAX_ISR_COUNT = 20;
158 bool fAliveStateChange =
false;
159 void (*fChangeNotify)(
int pin, uint16_t pwm);
161 static Private* priv()
163 static Private _priv;
167 static void ISR_generic(
byte isr)
169 Private* _priv = priv();
170 unsigned long now = micros();
171 bool state_now = digitalRead(_priv->fISRPin[isr]);
172 if (state_now != _priv->fISRLastState[isr])
174 if (state_now == _priv->fISRTriggerState[isr])
176 _priv->fISRTimer[isr] = now;
180 uint16_t pulseGap = (
unsigned int)(now - _priv->fISRTimer[isr]);
181 if (pulseGap > 850 && pulseGap < 2150)
183 _priv->fISRValue[isr] = pulseGap;
184 _priv->fISRMillis[isr] = millis();
186 _priv->fISRAge[isr] = now;
188 _priv->fISRLastState[isr] = state_now;
192 #define DEFINE_ISR_HANDLER(n) \
193 static void ISR_##n() \
219 #undef DEFINE_ISR_HANDLER