RSeries astromech firmware
ServoDispatchDirect.h
Go to the documentation of this file.
1 #ifndef ServoDispatchDirect_h
2 #define ServoDispatchDirect_h
3 
4 #ifdef USE_SERVO_DEBUG
5 #define SERVO_DEBUG_PRINT(s) DEBUG_PRINT(s)
6 #define SERVO_DEBUG_PRINTLN(s) DEBUG_PRINTLN(s)
7 #define SERVO_DEBUG_PRINT_HEX(s) DEBUG_PRINT_HEX(s)
8 #define SERVO_DEBUG_PRINTLN_HEX(s) DEBUG_PRINTLN_HEX(s)
9 #else
10 #define SERVO_DEBUG_PRINT(s)
11 #define SERVO_DEBUG_PRINTLN(s)
12 #define SERVO_DEBUG_PRINT_HEX(s)
13 #define SERVO_DEBUG_PRINTLN_HEX(s)
14 #endif
15 
16 #ifdef USE_VERBOSE_SERVO_DEBUG
17 #define VERBOSE_SERVO_DEBUG_PRINT(s) DEBUG_PRINT(s)
18 #define VERBOSE_SERVO_DEBUG_PRINTLN(s) DEBUG_PRINTLN(s)
19 #define VERBOSE_SERVO_DEBUG_PRINT_HEX(s) DEBUG_PRINT_HEX(s)
20 #define VERBOSE_SERVO_DEBUG_PRINTLN_HEX(s) DEBUG_PRINTLN_HEX(s)
21 #else
22 #define VERBOSE_SERVO_DEBUG_PRINT(s)
23 #define VERBOSE_SERVO_DEBUG_PRINTLN(s)
24 #define VERBOSE_SERVO_DEBUG_PRINT_HEX(s)
25 #define VERBOSE_SERVO_DEBUG_PRINTLN_HEX(s)
26 #endif
27 
28 #include "ServoDispatchPrivate.h"
29 
37 template <uint8_t numServos>
40 #ifndef ARDUINO_ARCH_ESP32
41  ,private ServoDispatchISR
42 #endif
43 {
44 public:
46  fLastTime(0)
47  {
48  #ifndef ARDUINO_ARCH_ESP32
49  const unsigned kDefaultPulseWidth = 1500;
50  auto priv = privates();
51  #endif
52  memset(fServos, '\0', sizeof(fServos));
53  for (uint16_t i = 0; i < numServos; i++)
54  {
55  ServoState* state = &fServos[i];
56  state->channel = i;
57  #ifndef ARDUINO_ARCH_ESP32
58  priv->pwm[i].ticks = convertMicrosecToTicks(kDefaultPulseWidth);
59  #endif
60  }
61  #ifndef ARDUINO_ARCH_ESP32
62  priv->ServoCount = numServos;
63  #endif
64  }
65 
67  fLastTime(0)
68  {
69  #ifndef ARDUINO_ARCH_ESP32
70  const unsigned kDefaultPulseWidth = 1500;
71  auto priv = privates();
72  #endif
73  memset(fServos, '\0', sizeof(fServos));
74  for (uint16_t i = 0; i < numServos; i++)
75  {
76  ServoState* state = &fServos[i];
77  uint8_t pin = pgm_read_uint16(&settings[i].pinNum);
78  #ifndef ARDUINO_ARCH_ESP32
79  pinMode(pin, OUTPUT);
80  #endif
81  state->channel = i;
82  state->startPulse = pgm_read_uint16(&settings[i].startPulse);
83  state->endPulse = pgm_read_uint16(&settings[i].endPulse);
84  /* netural defaults to start position */
85  state->neutralPulse = state->startPulse;
86  state->group = pgm_read_uint32(&settings[i].group);
87  state->posNow = state->neutralPulse;
88  #ifndef ARDUINO_ARCH_ESP32
89  priv->pwm[i].pin = pin;
90  priv->pwm[i].ticks = convertMicrosecToTicks(kDefaultPulseWidth);
91  #else
92  state->pin = (ServoDispatchESP32::validPWM(pin)) ? pin : 0;
93  #endif
94  }
95  #ifndef ARDUINO_ARCH_ESP32
96  priv->ServoCount = numServos;
97  #endif
98  }
99 
100  virtual uint16_t getNumServos() override
101  {
102  return numServos;
103  }
104 
105  virtual uint8_t getPin(uint16_t num) override
106  {
107  if (num < numServos)
108  {
109  #ifndef ARDUINO_ARCH_ESP32
110  auto priv = privates();
111  return priv->pwm[num].pin;
112  #else
113  ServoState* state = &fServos[num];
114  return state->pin;
115  #endif
116  }
117  return 0;
118  }
119 
120  virtual uint16_t getStart(uint16_t num) override
121  {
122  return (num < numServos) ? fServos[num].startPulse : 0;
123  }
124 
125  virtual uint16_t getEnd(uint16_t num) override
126  {
127  return (num < numServos) ? fServos[num].endPulse : 0;
128  }
129 
130  virtual uint16_t getMinimum(uint16_t num) override
131  {
132  return (num < numServos) ? fServos[num].getMinimum() : 0;
133  }
134 
135  virtual uint16_t getNeutral(uint16_t num) override
136  {
137  return (num < numServos) ? fServos[num].getNeutral() : 0;
138  }
139 
140  virtual uint16_t getMaximum(uint16_t num) override
141  {
142  return (num < numServos) ? fServos[num].getMaximum() : 0;
143  }
144 
145  virtual uint32_t getGroup(uint16_t num) override
146  {
147  return (num < numServos) ? fServos[num].group : 0;
148  }
149 
150  virtual uint16_t currentPos(uint16_t num) override
151  {
152  return (num < numServos) ? fServos[num].currentPos() : 0;
153  }
154 
155  virtual void setServo(uint16_t num, uint8_t pin, uint16_t startPulse, uint16_t endPulse, uint16_t neutralPulse, uint32_t group) override
156  {
157  #ifndef ARDUINO_ARCH_ESP32
158  const unsigned kDefaultPulseWidth = 1500;
159  auto priv = privates();
160  #endif
161  if (num < numServos)
162  {
163  ServoState* state = &fServos[num];
164  #ifndef ARDUINO_ARCH_ESP32
165  pinMode(pin, OUTPUT);
166  #endif
167  state->channel = num;
168  state->startPulse = startPulse;
169  state->endPulse = endPulse;
170  state->neutralPulse = neutralPulse;
171  state->group = group;
172  state->posNow = state->neutralPulse;
173  #ifndef ARDUINO_ARCH_ESP32
174  priv->pwm[num].pin = pin;
175  priv->pwm[num].ticks = convertMicrosecToTicks(kDefaultPulseWidth);
176  #else
177  state->pin = (ServoDispatchESP32::validPWM(pin)) ? pin : 0;
178  #endif
179  }
180  }
181 
182  virtual void stop() override
183  {
184  // Stop all servo movement
185  for (uint16_t i = 0; i < numServos; i++)
186  {
187  disable(i);
188  }
189  }
190 
191  virtual uint16_t scaleToPos(uint16_t num, float scale) override
192  {
193  uint16_t pos = 0;
194  if (num < numServos)
195  {
196  scale = min(max(0.0f, scale), 1.0f);
197  uint16_t startPulse = fServos[num].startPulse;
198  uint16_t endPulse = fServos[num].endPulse;
199  if (startPulse < endPulse)
200  {
201  pos = startPulse + (endPulse - startPulse) * scale;
202  }
203  else
204  {
205  pos = startPulse - (startPulse - endPulse) * scale;
206  }
207  }
208  return pos;
209  }
210 
211  virtual void setup() override
212  {
213  #ifdef ARDUINO_ARCH_ESP32
214  // TODO only configure necessary number of timers
215  ServoDispatchESP32::configureTimer(0);
216  ServoDispatchESP32::configureTimer(1);
217  ServoDispatchESP32::configureTimer(2);
218  ServoDispatchESP32::configureTimer(3);
219  // Attach and detach PWM pin to clear out any signals
220  for (int i = 0; i < numServos; i++)
221  {
222  ServoState* state = &fServos[i];
223  fPWM[i].attachPin(state->pin, REFRESH_CPS, DEFAULT_TIMER_WIDTH);
224  fPWM[i].detachPin(state->pin);
225  }
226  #endif
227  }
228 
229  virtual bool isActive(uint16_t num) override
230  {
231  if (num < numServos)
232  {
233  #ifndef ARDUINO_ARCH_ESP32
234  auto priv = privates();
235  return priv->pwm[num].isActive;
236  #else
237  return fPWM[num].attached();
238  #endif
239  }
240  return false;
241  }
242 
243  virtual void disable(uint16_t num) override
244  {
245  if (num < numServos)
246  {
247  ServoState* state = &fServos[num];
248  state->init();
249  #ifndef ARDUINO_ARCH_ESP32
250  auto priv = privates();
251  priv->pwm[num].isActive = false;
252  digitalWrite(priv->pwm[num].pin, LOW);
253  #else
254  if (fPWM[num].attached())
255  {
256  fPWM[num].detachPin(state->pin);
257  }
258  #endif
259  }
260  }
261 
262  virtual void animate() override
263  {
264  uint32_t now = millis();
265  if (fLastTime + 1 < now)
266  {
267  for (int i = 0; i < numServos; i++)
268  {
269  ServoState* state = &fServos[i];
270  if (state->finishTime != 0)
271  {
272  state->move(this, now);
273  }
274  else if (state->detachTime > 0 && state->detachTime < millis())
275  {
276  disable(i);
277  }
278  }
279  fLastTime = now = millis();
280  }
281  }
282 
283  virtual void setPWM(uint16_t channel, uint16_t targetLength) override
284  {
285  #ifndef ARDUINO_ARCH_ESP32
286  auto priv = privates();
287  if (channel < MAX_SERVOS) // ensure channel is valid
288  {
289  if (!priv->pwm[channel].isActive)
290  {
291  initISR(fServos[channel].channel);
292  }
293 
294  priv->pwm[channel].value = targetLength;
295  // if (value < SERVO_MIN()) // ensure pulse width is valid
296  // value = SERVO_MIN();
297  // else if (value > SERVO_MAX())
298  // value = SERVO_MAX();
299 
300  targetLength -= kTrimDuration;
301  targetLength = convertMicrosecToTicks(targetLength);
302 
303  uint8_t oldSREG = SREG;
304  // uint16_t oldticks;
305  cli();
306  // oldticks = priv->pwm[channel].ticks;
307  priv->pwm[channel].ticks = targetLength;
308  SREG = oldSREG;
309  priv->pwm[channel].speed = 0;
310  sei();
311  // if (oldticks != targetLength)
312  // {
313  // DEBUG_PRINT("setPWM ");
314  // DEBUG_PRINT(channel);
315  // DEBUG_PRINT(" target: ");
316  // DEBUG_PRINTLN(targetLength);
317  // }
318  }
319  #else
320  if (fPWM[channel].attached())
321  {
322  uint32_t ticks = convertMicrosecToTicks(targetLength);
323  fPWM[channel].write(ticks);
324  // Serial.print("PWM pin="); Serial.print(fServos[channel].pin); Serial.print(" = "); Serial.println(targetLength);
325  }
326  #endif
327  }
328 
329 private:
330  enum
331  {
332  kMinPulseWidth = 544,
333  kMaxPulseWidth = 2400,
334  kTrimDuration = 2
335  };
336 
337  struct ServoState
338  {
339  uint16_t currentPos()
340  {
341  return posNow;
342  }
343 
344  uint16_t getMinimum()
345  {
346  return min(startPulse, endPulse);
347  }
348 
349  uint16_t getNeutral()
350  {
351  return neutralPulse;
352  }
353 
354  uint16_t getMaximum()
355  {
356  return max(startPulse, endPulse);
357  }
358 
359  void move(ServoDispatchDirect<numServos>* dispatch, uint32_t timeNow)
360  {
361  if (finishTime != 0)
362  {
363  if (timeNow < startTime)
364  {
365  /* wait */
366  }
367  else if (timeNow >= finishTime)
368  {
369  posNow = finishPos;
370  doMove(dispatch, timeNow);
371  init();
372  detachTime = timeNow + 500;
373  }
374  else if (lastMoveTime != timeNow)
375  {
376  uint32_t timeSinceLastMove = timeNow - startTime;
377  uint32_t denominator = finishTime - startTime;
378  float (*useMethod)(float) = easingMethod;
379  if (useMethod == nullptr)
380  useMethod = Easing::LinearInterpolation;
381  float fractionChange = useMethod(float(timeSinceLastMove)/float(denominator));
382  int distanceToMove = float(deltaPos) * fractionChange;
383  uint16_t newPos = startPosition + distanceToMove;
384  if (newPos != posNow)
385  {
386  posNow = startPosition + distanceToMove;
387  doMove(dispatch, timeNow);
388  }
389  }
390  }
391  }
392 
393  void moveToPulse(ServoDispatchDirect<numServos>* dispatch, uint32_t startDelay, uint32_t moveTime, uint16_t startPos, uint16_t pos)
394  {
395  uint32_t timeNow = millis();
396 
397  startTime = startDelay + timeNow;
398  finishTime = moveTime + startTime;
399  finishPos = min(getMaximum(), max(getMinimum(), pos));
400  posNow = startPosition = startPos;
401  deltaPos = finishPos - posNow;
402  doMove(dispatch, timeNow);
403  }
404  uint8_t channel;
405  uint32_t group;
406  uint16_t startPulse;
407  uint16_t endPulse;
408  uint16_t neutralPulse;
409  uint32_t startTime;
410  uint32_t finishTime;
411  uint32_t lastMoveTime;
412  uint16_t finishPos;
413  uint16_t startPosition;
414  uint16_t posNow;
415  uint32_t detachTime;
416  int deltaPos;
417  float (*easingMethod)(float completion) = nullptr;
418  #ifdef ARDUINO_ARCH_ESP32
419  uint8_t pin;
420  uint32_t ticks;
421  #endif
422 
423  void doMove(ServoDispatchDirect<numServos>* dispatch, uint32_t timeNow)
424  {
425  #ifdef USE_SERVO_DEBUG
426  SERVO_DEBUG_PRINT("PWM ");
427  SERVO_DEBUG_PRINT(channel);
428  SERVO_DEBUG_PRINT(" ");
429  SERVO_DEBUG_PRINTLN(posNow);
430  #endif
431  dispatch->setPWM(channel, posNow);
432  #if 0//def USE_SMQ
433  if (SMQ::sendTopic("PWM"))
434  {
435  SMQ::send_uint8(F("num"), channel);
436  SMQ::send_float(F("len"), posNow);
437  SMQ::send_end();
438  }
439  #endif
440  lastMoveTime = timeNow;
441  }
442 
443  void init()
444  {
445  finishTime = 0;
446  lastMoveTime = 0;
447  finishPos = 0;
448  detachTime = 0;
449  }
450  };
451 
453 
454  virtual void _moveServoToPulse(uint16_t num, uint32_t startDelay, uint32_t moveTime, uint16_t startPos, uint16_t pos) override
455  {
456  if (num < numServos)
457  {
458  #ifndef ARDUINO_ARCH_ESP32
459  initISR(fServos[num].channel);
460  #else
461  if (fServos[num].pin && !fPWM[num].attached())
462  {
463  fPWM[num].attachPin(fServos[num].pin, REFRESH_CPS, DEFAULT_TIMER_WIDTH);
464  SERVO_DEBUG_PRINTLN("Attaching servo : "+String(fServos[num].pin)+" on PWM "+String(fPWM[num].getChannel())+" PULSE "+pos);
465  }
466  #endif
467  fServos[num].moveToPulse(this, startDelay, moveTime, startPos, pos);
468  fLastTime = 0;
469  }
470  }
471 
473 
474  // Move all servos matching servoGroupMask starting at startDelay in moveTimeMin-moveTimeMax to position pos
475  virtual void _moveServosToPulse(uint32_t servoGroupMask, uint32_t startDelay, uint32_t moveTimeMin, uint32_t moveTimeMax, uint16_t pos) override
476  {
477  for (uint16_t i = 0; i < numServos; i++)
478  {
479  uint32_t moveTime = (moveTimeMin != moveTimeMax) ? random(moveTimeMin, moveTimeMax) : moveTimeMax;
480  if ((fServos[i].group & servoGroupMask) != 0)
481  {
482  moveToPulse(i, startDelay, moveTime, fServos[i].currentPos(), pos);
483  }
484  }
485  }
486 
487  virtual void _moveServosByPulse(uint32_t servoGroupMask, uint32_t startDelay, uint32_t moveTimeMin, uint32_t moveTimeMax, int16_t pos) override
488  {
489  for (uint16_t i = 0; i < numServos; i++)
490  {
491  uint32_t moveTime = (moveTimeMin != moveTimeMax) ? random(moveTimeMin, moveTimeMax) : moveTimeMax;
492  if ((fServos[i].group & servoGroupMask) != 0)
493  {
494  int16_t curpos = fServos[i].currentPos();
495  moveToPulse(i, startDelay, moveTime, curpos, curpos + pos);
496  }
497  }
498  }
499 
501 
502  virtual void _moveServoSetToPulse(uint32_t servoGroupMask, uint32_t servoSetMask, uint32_t startDelay, uint32_t moveTimeMin, uint32_t moveTimeMax, uint16_t onPos, uint16_t offPos) override
503  {
504  byte bitShift = 31;
505  for (uint16_t i = 0; i < numServos; i++)
506  {
507  if ((fServos[i].group & servoGroupMask) == 0)
508  continue;
509  uint32_t moveTime = (moveTimeMin != moveTimeMax) ? random(moveTimeMin, moveTimeMax) : moveTimeMax;
510  bool on = ((servoSetMask & (1L<<bitShift)) != 0);
511  moveToPulse(i, startDelay, moveTime, fServos[i].currentPos(), (on) ? onPos : offPos);
512  if (bitShift-- == 0)
513  break;
514  }
515  }
516 
517  virtual void _moveServoSetByPulse(uint32_t servoGroupMask, uint32_t servoSetMask, uint32_t startDelay, uint32_t moveTimeMin, uint32_t moveTimeMax, int16_t onPos, int16_t offPos) override
518  {
519  byte bitShift = 31;
520  for (uint16_t i = 0; i < numServos; i++)
521  {
522  if ((fServos[i].group & servoGroupMask) == 0)
523  continue;
524  uint32_t moveTime = (moveTimeMin != moveTimeMax) ? random(moveTimeMin, moveTimeMax) : moveTimeMax;
525  bool on = ((servoSetMask & (1L<<bitShift)) != 0);
526  int16_t curpos = fServos[i].currentPos();
527  moveToPulse(i, startDelay, moveTime, curpos, curpos + ((on) ? onPos : offPos));
528  if (bitShift-- == 0)
529  break;
530  }
531  }
532 
534 
535  virtual void _moveServosTo(uint32_t servoGroupMask, uint32_t startDelay, uint32_t moveTimeMin, uint32_t moveTimeMax, float pos) override
536  {
537  for (uint16_t i = 0; i < numServos; i++)
538  {
539  uint32_t moveTime = (moveTimeMin != moveTimeMax) ? random(moveTimeMin, moveTimeMax) : moveTimeMax;
540  if ((fServos[i].group & servoGroupMask) != 0)
541  {
542  moveToPulse(i, startDelay, moveTime, fServos[i].currentPos(), scaleToPos(i, pos));
543  }
544  }
545  }
546 
547  virtual void _moveServoSetTo(uint32_t servoGroupMask, uint32_t servoSetMask, uint32_t startDelay, uint32_t moveTimeMin, uint32_t moveTimeMax, float onPos, float offPos, float (*onEasingMethod)(float), float (*offEasingMethod)(float)) override
548  {
549  byte bitShift = 31;
550  for (uint16_t i = 0; i < numServos; i++)
551  {
552  if ((fServos[i].group & servoGroupMask) == 0)
553  continue;
554  uint32_t moveTime = (moveTimeMin != moveTimeMax) ? random(moveTimeMin, moveTimeMax) : moveTimeMax;
555  bool on = ((servoSetMask & (1L<<bitShift)) != 0);
556  VERBOSE_SERVO_DEBUG_PRINT("moveToPulse on=");
558  VERBOSE_SERVO_DEBUG_PRINT(" onPos=");
560  VERBOSE_SERVO_DEBUG_PRINT(" offPos=");
562  VERBOSE_SERVO_DEBUG_PRINT(" pos=");
563  VERBOSE_SERVO_DEBUG_PRINTLN(scaleToPos(i, (on) ? onPos : offPos));
564  if (on)
565  {
566  if (onEasingMethod != nullptr)
567  setServoEasingMethod(i, onEasingMethod);
568  }
569  else if (offEasingMethod != nullptr)
570  {
571  setServoEasingMethod(i, offEasingMethod);
572  }
573  moveToPulse(i, startDelay, moveTime, fServos[i].currentPos(), scaleToPos(i, (on) ? onPos : offPos));
574  if (bitShift-- == 0)
575  break;
576  }
577  }
578 
580 
581  virtual void _setServoEasingMethod(uint16_t num, float (*easingMethod)(float completion))
582  {
583  if (num < numServos && fServos[num].channel != 0)
584  {
585  fServos[num].easingMethod = easingMethod;
586  }
587  }
588 
589  virtual void _setServosEasingMethod(uint32_t servoGroupMask, float (*easingMethod)(float completion))
590  {
591  for (uint16_t i = 0; i < numServos; i++)
592  {
593  if ((fServos[i].group & servoGroupMask) != 0)
594  {
595  fServos[i].easingMethod = easingMethod;
596  }
597  }
598  }
599 
600  virtual void _setEasingMethod(float (*easingMethod)(float completion))
601  {
602  for (uint16_t i = 0; i < numServos; i++)
603  {
604  fServos[i].easingMethod = easingMethod;
605  }
606  }
607 
609 
610  uint32_t fLastTime;
611  ServoState fServos[numServos];
612 
613 private:
614  inline uint16_t pgm_read_uint16(const uint16_t* p)
615  {
616  #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega32U4__) || \
617  defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__) || \
618  defined(__AVR_ATmega128__) ||defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
619  return pgm_read_word(p);
620  #else
621  return *p;
622  #endif
623  }
624 
625  inline uint32_t pgm_read_uint32(const uint32_t* p)
626  {
627  #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega32U4__) || \
628  defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__) || \
629  defined(__AVR_ATmega128__) ||defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
630  return pgm_read_dword(p);
631  #else
632  return *p;
633  #endif
634  }
635 
636 #ifdef ARDUINO_ARCH_ESP32
637  const int REFRESH_CPS = 50;
638  const int REFRESH_USEC = 20000;
639  const int DEFAULT_TIMER_WIDTH = 16;
640  const int DEFAULT_TIMER_WIDTH_TICKS = 65536;
641  ServoDispatchESP32 fPWM[numServos];
642  int convertMicrosecToTicks(int usec)
643  {
644  return (int)((float)usec / ((float)REFRESH_USEC / (float)DEFAULT_TIMER_WIDTH_TICKS)*(((float)REFRESH_CPS)/50.0));
645  }
646 
647  int convertTicksToMicrosec(int ticks)
648  {
649  return (int)((float)ticks * ((float)REFRESH_USEC / (float)DEFAULT_TIMER_WIDTH_TICKS)/(((float)REFRESH_CPS)/50.0));
650  }
651 #endif
652 };
653 
654 #endif
ServoDispatchDirect
Implements ServoDispatch dirctly on PWM enabled outputs.
Definition: ServoDispatchDirect.h:38
SERVO_DEBUG_PRINT
#define SERVO_DEBUG_PRINT(s)
Definition: ServoDispatchDirect.h:10
ServoDispatchDirect::getGroup
virtual uint32_t getGroup(uint16_t num) override
Definition: ServoDispatchDirect.h:145
ServoDispatchDirect::getMaximum
virtual uint16_t getMaximum(uint16_t num) override
Definition: ServoDispatchDirect.h:140
VERBOSE_SERVO_DEBUG_PRINTLN
#define VERBOSE_SERVO_DEBUG_PRINTLN(s)
Definition: ServoDispatchDirect.h:23
ServoDispatchDirect::setServo
virtual void setServo(uint16_t num, uint8_t pin, uint16_t startPulse, uint16_t endPulse, uint16_t neutralPulse, uint32_t group) override
Definition: ServoDispatchDirect.h:155
AnimatedEvent
Base class for all animated devices. AnimatedEvent::animate() is called for each device once through ...
Definition: AnimatedEvent.h:18
ServoDispatchDirect::ServoDispatchDirect
ServoDispatchDirect(const ServoSettings *settings)
Definition: ServoDispatchDirect.h:66
SMQ::send_end
static void send_end()
Definition: ReelTwoSMQ.h:463
ServoDispatchDirect::animate
virtual void animate() override
Subclasses must implement this function to run through a single frame of animation/activity.
Definition: ServoDispatchDirect.h:262
SetupEvent
Base class for all devices that require setup that cannot happen in the constructor....
Definition: SetupEvent.h:15
SMQ::sendTopic
static bool sendTopic(const smq_id id)
Definition: ReelTwoSMQ.h:155
ServoDispatchDirect::getStart
virtual uint16_t getStart(uint16_t num) override
Definition: ServoDispatchDirect.h:120
ServoDispatchDirect::stop
virtual void stop() override
Definition: ServoDispatchDirect.h:182
ServoDispatchPrivate.h
ServoDispatchDirect::getNeutral
virtual uint16_t getNeutral(uint16_t num) override
Definition: ServoDispatchDirect.h:135
ServoDispatchDirect::currentPos
virtual uint16_t currentPos(uint16_t num) override
Definition: ServoDispatchDirect.h:150
ServoDispatchDirect::getMinimum
virtual uint16_t getMinimum(uint16_t num) override
Definition: ServoDispatchDirect.h:130
ServoDispatchDirect::isActive
virtual bool isActive(uint16_t num) override
Definition: ServoDispatchDirect.h:229
SERVO_DEBUG_PRINTLN
#define SERVO_DEBUG_PRINTLN(s)
Definition: ServoDispatchDirect.h:11
ServoDispatchDirect::getNumServos
virtual uint16_t getNumServos() override
Definition: ServoDispatchDirect.h:100
ServoSettings
Settings for individual servos.
Definition: ServoDispatch.h:55
SMQ::send_float
static void send_float(const msg_id id, float val)
Definition: ReelTwoSMQ.h:364
ServoDispatchDirect::scaleToPos
virtual uint16_t scaleToPos(uint16_t num, float scale) override
Definition: ServoDispatchDirect.h:191
ServoDispatch
Servo interace implemented eitehr by ServoDispatchPCA9685 or ServoDispatchDirect.
Definition: ServoDispatch.h:83
ServoDispatchDirect::setup
virtual void setup() override
Subclasses must implement this function to perform any necessary setup that cannot happen in the cons...
Definition: ServoDispatchDirect.h:211
ServoDispatchDirect::disable
virtual void disable(uint16_t num) override
Definition: ServoDispatchDirect.h:243
ServoDispatchDirect::getPin
virtual uint8_t getPin(uint16_t num) override
Definition: ServoDispatchDirect.h:105
SMQ::send_uint8
static void send_uint8(const msg_id id, uint8_t val)
Definition: ReelTwoSMQ.h:292
ServoDispatch::moveToPulse
void moveToPulse(uint16_t num, uint32_t startDelay, uint32_t moveTime, uint16_t pos)
Definition: ServoDispatch.h:198
MAX_SERVOS
#define MAX_SERVOS
Definition: ServoDispatchPrivate.h:29
ServoDispatchDirect::getEnd
virtual uint16_t getEnd(uint16_t num) override
Definition: ServoDispatchDirect.h:125
ServoDispatchDirect::setPWM
virtual void setPWM(uint16_t channel, uint16_t targetLength) override
Definition: ServoDispatchDirect.h:283
VERBOSE_SERVO_DEBUG_PRINT
#define VERBOSE_SERVO_DEBUG_PRINT(s)
Definition: ServoDispatchDirect.h:22
ServoDispatchDirect::ServoDispatchDirect
ServoDispatchDirect()
Definition: ServoDispatchDirect.h:45
ServoDispatch::setServoEasingMethod
void setServoEasingMethod(uint16_t num, float(*easingMethod)(float completion))
Definition: ServoDispatch.h:312
Easing::LinearInterpolation
static float LinearInterpolation(float p)
Definition: ServoEasing.h:48