ServoEasing
ServoEasing.hpp
Go to the documentation of this file.
1 /*
2  * ServoEasing.hpp
3  *
4  * Enables smooth movement from one servo position to another.
5  * Linear as well as other ease movements (e.g. cubic) for all servos attached to the Arduino Servo library are provided.
6  * Interface is in degree but internally only microseconds (if using Servo library) or units (if using PCA9685 expander) are used,
7  * since the resolution is better and we avoid the map function on every Servo.write().
8  * The blocking functions wait for 20 ms since this is the default refresh time of the used Servo library.
9  *
10  * The AVR Servo library supports only one timer, which means not more than 12 servos are supported using this library.
11  *
12  * Copyright (C) 2019-2026 Armin Joachimsmeyer
13  * armin.joachimsmeyer@gmail.com
14  *
15  * This file is part of ServoEasing https://github.com/ArminJo/ServoEasing.
16  *
17  * ServoEasing is free software: you can redistribute it and/or modify
18  * it under the terms of the GNU General Public License as published by
19  * the Free Software Foundation, either version 3 of the License, or
20  * (at your option) any later version.
21  *
22  * This program is distributed in the hope that it will be useful,
23  * but WITHOUT ANY WARRANTY; without even the implied warranty of
24  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
25  * See the GNU General Public License for more details.
26  *
27  * You should have received a copy of the GNU General Public License
28  * along with this program. If not, see <http://www.gnu.org/licenses/gpl.html>.
29  */
30 
31 /*
32  * This library can be configured at compile time by the following options / macros:
33  * For more details see: https://github.com/ArminJo/ServoEasing?tab=readme-ov-file#compile-options--macros-for-this-library
34  *
35  * - USE_PCA9685_SERVO_EXPANDER Enables the use of the PCA9685 I2C expander chip/board.
36  * - USE_SERVO_LIB Use of PCA9685 normally disables use of regular servo library. You can force additional using of regular servo library by defining USE_SERVO_LIB.
37  * - USE_LIGHTWEIGHT_SERVO_LIBRARY Makes the servo pulse generating immune to other libraries blocking interrupts for a longer time like SoftwareSerial, Adafruit_NeoPixel and DmxSimple.
38  * - PROVIDE_ONLY_LINEAR_MOVEMENT Disables all but LINEAR movement. Saves up to 1540 bytes program memory.
39  * - DISABLE_COMPLEX_FUNCTIONS Disables the SINE, CIRCULAR, BACK, ELASTIC, BOUNCE and PRECISION easings.
40  * - MAX_EASING_SERVOS Saves 4 byte RAM per servo.
41  * - DISABLE_MICROS_AS_DEGREE_PARAMETER Disables passing also microsecond values as (target angle) parameter. Saves 128 bytes program memory.
42  * - PRINT_FOR_SERIAL_PLOTTER Generate serial output for Arduino Plotter (Ctrl-Shift-L).
43  */
44 
45 #ifndef _SERVO_EASING_HPP
46 #define _SERVO_EASING_HPP
47 
48 #include <Arduino.h>
49 
50 #include "ServoEasing.h"
51 
52 #if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY) && (defined(__AVR_ATmega328P__) || defined(__AVR_ATmega328__) || defined (__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__))
53 #include "LightweightServo.hpp" // include sources of LightweightServo library
54 #endif
55 
56 /*
57  * Enable this to see information on each call.
58  * Since there should be no library which uses Serial, it should only be enabled for development purposes.
59  */
60 #if defined(TRACE)
61 #define LOCAL_TRACE
62 #define LOCAL_DEBUG // Propagate debug level
63 #else
64 //#define LOCAL_TRACE // This enables trace output only for this file
65 # if defined(DEBUG)
66 #define LOCAL_DEBUG
67 # else
68 //#define LOCAL_DEBUG // This enables debug output only for this file
69 # endif
70 #endif
71 
72 // Enable this if you want to measure timing by toggling pin12 on an arduino
73 //#define MEASURE_SERVO_EASING_INTERRUPT_TIMING
74 #if defined(MEASURE_SERVO_EASING_INTERRUPT_TIMING)
75 #include "digitalWriteFast.h"
76 #define TIMING_OUTPUT_PIN 12
77 #endif
78 
79 #if defined(ESP8266) || defined(ESP32)
80 //# if defined(ESP32)
81 //#include "esp_task_wdt.h" // for esp_task_wdt_reset();
82 //# endif
83 #include "Ticker.h" // for ServoEasingInterrupt functions
84 Ticker Timer20ms;
85 
86 // BluePill in 2 flavors
87 #elif defined(STM32F1xx) // for "Generic STM32F1 series / STMicroelectronics:stm32" from STM32 Boards from STM32 cores of Arduino Board manager
88 // https://github.com/stm32duino/BoardManagerFiles/raw/master/STM32/package_stm_index.json
89 #include <HardwareTimer.h> // 4 timers and 3. timer is used for tone(), 2. for Servo
90 /*
91  * Use timer 4 as IRMP timer.
92  * Timer 4 blocks PB6, PB7, PB8, PB9, so if you require one of them as Servo output, you must choose another timer.
93  */
94 HardwareTimer Timer20ms(TIM1);
95 
96 #elif defined(__STM32F1__) // or ARDUINO_ARCH_STM32F1 for "Generic STM32F103C series / stm32duino:STM32F1" from STM32F1 Boards (STM32duino.com) of Arduino Board manager
97 // http://dan.drown.org/stm32duino/package_STM32duino_index.json
98 #include <HardwareTimer.h>
99 # if defined(STM32_HIGH_DENSITY)
100 HardwareTimer Timer20ms(7); // 8 timers and 8. timer is used for tone()
101 # else
102 /*
103  * Use timer 3 for ServoEasingInterrupt functions.
104  * Timer 3 blocks PA6, PA7, PB0, PB1, so if you required one of them as Servo output, you must choose another timer.
105  */
106 HardwareTimer Timer20ms(3); // 4 timers and 4. timer is used for tone()
107 # endif
108 
109 #elif defined(__SAM3X8E__) // Arduino DUE
110 /*
111  * Timer 0 to 5 are used by Servo library (by defining handlers)
112  *
113  * Timer 6 is TC2 channel 0
114  * Timer 7 is TC2 channel 1
115  * Timer 8 is TC2 channel 2
116  *
117  * We use timer 8 here
118  */
119 #define TC_FOR_20_MS_TIMER TC2
120 #define CHANNEL_FOR_20_MS_TIMER 2
121 #define ID_TC_FOR_20_MS_TIMER ID_TC8 // Timer 8 is TC2 channel 2
122 #define IRQn_FOR_20_MS_TIMER TC8_IRQn
123 #define HANDLER_FOR_20_MS_TIMER TC8_Handler
124 
125 #elif defined(ARDUINO_ARCH_MBED) // Arduino Nano 33 BLE + Sparkfun Apollo3
126 mbed::Ticker Timer20ms;
127 
128 /*************************************************************************************************************************************
129  * RP2040 based boards for pico core
130  * https://github.com/earlephilhower/arduino-pico
131  * https://github.com/earlephilhower/arduino-pico/releases/download/global/package_rp2040_index.json
132  * Can use any pin for PWM, no timer restrictions
133  *************************************************************************************************************************************/
134 #elif defined(ARDUINO_ARCH_RP2040) // Raspberry Pi Pico, Adafruit Feather RP2040, etc.
135 #include "pico/time.h"
136 repeating_timer_t Timer20ms;
138 // The timer callback has a parameter and a return value
139 bool handleServoTimerInterruptHelper(repeating_timer_t*) {
141  return true;
142 }
143 
144 #elif defined(TEENSYDUINO)
145 // common for all Teensy
146 IntervalTimer Timer20ms;
147 #endif
148 
149 volatile bool ServoEasing::sInterruptsAreActive = false; // true if interrupts are still active, i.e. at least one Servo is moving with interrupts.
150 
155 uint_fast8_t ServoEasing::sServoArrayMaxIndex = 0; // maximum index of an attached servo in ServoEasing::ServoEasingArray[]
163 
164 const char easeTypeLinear[] PROGMEM = "linear";
165 #if !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
166 const char easeTypeQuadratic[] PROGMEM = "quadratic";
167 const char easeTypeCubic[] PROGMEM = "cubic";
168 const char easeTypeQuartic[] PROGMEM = "quartic";
169 const char easeTypePrecision[] PROGMEM = "precision";
170 const char easeTypeUser[] PROGMEM = "user";
171 const char easeTypeNotDefined[] PROGMEM = "";
172 const char easeTypeDummy[] PROGMEM = "dummy";
173 # if !defined(DISABLE_COMPLEX_FUNCTIONS)
174 const char easeTypeSine[] PROGMEM = "sine";
175 const char easeTypeCircular[] PROGMEM = "circular";
176 const char easeTypeBack[] PROGMEM = "back";
177 const char easeTypeElastic[] PROGMEM = "elastic";
178 const char easeTypeBounce[] PROGMEM = "bounce";
179 # endif
180 #endif // !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
181 
182 const char *const easeTypeStrings[] PROGMEM = { easeTypeLinear
183 #if !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
184  , easeTypeQuadratic, easeTypeCubic, easeTypeQuartic, easeTypeNotDefined, easeTypeNotDefined, easeTypeUser, easeTypeDummy,
185 # if !defined(DISABLE_COMPLEX_FUNCTIONS)
186  easeTypeSine, easeTypeCircular, easeTypeBack, easeTypeElastic, easeTypeBounce, easeTypePrecision
187 # endif
188 #endif
189  };
190 
191 #if defined(USE_PCA9685_SERVO_EXPANDER)
192 //#define USE_SOFT_I2C_MASTER // Saves 2110 bytes program memory and 200 bytes RAM compared with Arduino Wire
193 # if defined(USE_SOFT_I2C_MASTER)
194 #include "SoftI2CMasterConfig.h"
195 #include "SoftI2CMaster.h"
196 # endif // defined(USE_SOFT_I2C_MASTER)
197 
198 # if !defined _BV
199 # define _BV(bit) (1 << (bit))
200 # endif
201 // Constructor with I2C address required
202 #if defined(USE_SOFT_I2C_MASTER)
203 ServoEasing::ServoEasing(uint8_t aPCA9685I2CAddress) // @suppress("Class members should be properly initialized")
204 #else
205 ServoEasing::ServoEasing(uint8_t aPCA9685I2CAddress, TwoWire *aI2CClass) // @suppress("Class members should be properly initialized")
206 #endif
207  {
208  mPCA9685I2CAddress = aPCA9685I2CAddress;
209 #if !defined(USE_SOFT_I2C_MASTER)
210  mI2CClass = aI2CClass;
211 #endif
212 
213  // On an ESP8266 it was NOT initialized to 0 :-(.
216  mServoMoves = false;
217  mOperateServoReverse = false;
218 
219 #if defined(USE_SERVO_LIB)
220  mServoIsConnectedToExpander = true;
221 #endif
222 #if !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
224 # if defined(ENABLE_EASE_USER)
225  mUserEaseInFunction = nullptr;
226 # endif
227 #endif
229 
230 #if defined(ENABLE_MIN_AND_MAX_CONSTRAINTS)
231  // initialize with some reasonable values
232  mMinMicrosecondsOrUnits = DEFAULT_MICROSECONDS_FOR_0_DEGREE / 2;
234 #endif
235 
236 #if defined(MEASURE_SERVO_EASING_INTERRUPT_TIMING)
237  pinMode(TIMING_OUTPUT_PIN, OUTPUT);
238 #endif
239 }
240 
241 void ServoEasing::I2CInit() {
242 // Initialize I2C
243 #if defined(USE_SOFT_I2C_MASTER)
244  i2c_init(); // Initialize everything and check for bus lockup
245 #else
246  mI2CClass->begin();
247  mI2CClass->setClock(I2C_CLOCK_FREQUENCY); // .8 MHz - 1 MHz from datasheet does not work for my Arduino Nano, maybe because of parasitic breadboard capacities
248 # if defined (ARDUINO_ARCH_AVR) // Other platforms do not have this new function
249  mI2CClass->setWireTimeout(); // Sets default timeout of 25 ms.
250 # endif
251 #endif
252 }
256 void ServoEasing::PCA9685Reset() {
257  // Send software reset to expander(s)
258 #if defined(USE_SOFT_I2C_MASTER)
259  i2c_start(PCA9685_GENERAL_CALL_ADDRESS << 1);
260  i2c_write(PCA9685_SOFTWARE_RESET);
261  i2c_stop();
262 #else
263  mI2CClass->beginTransmission(PCA9685_GENERAL_CALL_ADDRESS);
264  mI2CClass->write(PCA9685_SOFTWARE_RESET);
265  mI2CClass->endTransmission();
266 #endif
267 }
268 
273 void ServoEasing::PCA9685Init() {
274  // Set expander to 20 ms period
275  I2CWriteByte(PCA9685_MODE1_REGISTER, _BV(PCA9685_MODE_1_SLEEP)); // go to sleep
276  I2CWriteByte(PCA9685_PRESCALE_REGISTER, PCA9685_PRESCALER_FOR_20_MS); // set the prescaler
277  I2CWriteByte(PCA9685_MODE1_REGISTER, _BV(PCA9685_MODE_1_AUTOINCREMENT)); // reset sleep and enable auto increment
278  delay(2); // > 500 us according to datasheet
279 }
280 
285 void ServoEasing::PCA9685InitWithExternalClock(uint32_t aExternalClockFrequencyHertz) {
286  // Set expander to 20 ms period
287  I2CWriteByte(PCA9685_MODE1_REGISTER, _BV(PCA9685_MODE_1_SLEEP)); // go to sleep
288  I2CWriteByte(PCA9685_MODE1_REGISTER, (_BV(PCA9685_MODE1_EXTCLK) | _BV(PCA9685_MODE_1_SLEEP))); // switch to external clock input
289  I2CWriteByte(PCA9685_PRESCALE_REGISTER, (aExternalClockFrequencyHertz / (4096L * 50)) -1); // set the prescaler
290  I2CWriteByte(PCA9685_MODE1_REGISTER, _BV(PCA9685_MODE_1_AUTOINCREMENT)); // reset sleep and enable auto increment
291  delay(2); // > 500 us according to datasheet
292 }
293 
303 void ServoEasing::PCA9685Init(uint32_t aActualPCA9685ClockFrequencyHertz) {
304  // Set expander to 20 ms period
305  I2CWriteByte(PCA9685_MODE1_REGISTER, _BV(PCA9685_MODE_1_SLEEP)); // go to sleep
306  I2CWriteByte(PCA9685_PRESCALE_REGISTER, (aActualPCA9685ClockFrequencyHertz / (4096L * 50)) -1); // set the prescaler
307  I2CWriteByte(PCA9685_MODE1_REGISTER, _BV(PCA9685_MODE_1_AUTOINCREMENT)); // reset sleep and enable auto increment
308  delay(2); // > 500 us according to datasheet
309 }
310 
311 void ServoEasing::I2CWriteByte(uint8_t aAddress, uint8_t aData) {
312 #if defined(USE_SOFT_I2C_MASTER)
313  i2c_start(mPCA9685I2CAddress << 1);
314  i2c_write(aAddress);
315  i2c_write(aData);
316  i2c_stop();
317 #else
318  mI2CClass->beginTransmission(mPCA9685I2CAddress);
319  mI2CClass->write(aAddress);
320  mI2CClass->write(aData);
321 # if defined(LOCAL_DEBUG)
322  uint8_t tWireReturnCode = mI2CClass->endTransmission();
323  if (tWireReturnCode != 0) {
324  // I have seen this at my ESP32 module :-( - but it is no buffer overflow.
325  Serial.print((char) (tWireReturnCode + '0')); // Error enum i2c_err_t: I2C_ERROR_ACK = 2, I2C_ERROR_TIMEOUT = 3
326  }
327 # else
328  mI2CClass->endTransmission();
329 # endif
330 #endif
331 }
332 
339 void ServoEasing::setPWM(uint16_t aPWMOffValueAsUnits) {
340 #if defined(USE_SOFT_I2C_MASTER)
341  i2c_start(mPCA9685I2CAddress << 1);
342  i2c_write((PCA9685_FIRST_PWM_REGISTER + 2) + 4 * mServoPin);
343  i2c_write(aPWMOffValueAsUnits);
344  i2c_write(aPWMOffValueAsUnits >> 8);
345  i2c_stop();
346 #else
347  mI2CClass->beginTransmission(mPCA9685I2CAddress);
348  // +2 since we we do set the OFF value and not the ON value, which is fixed at 0
349  mI2CClass->write((PCA9685_FIRST_PWM_REGISTER + 2) + 4 * mServoPin); // 4 * mServoPin is the register offset
350  mI2CClass->write(aPWMOffValueAsUnits);
351  mI2CClass->write(aPWMOffValueAsUnits >> 8);
352 # if defined(LOCAL_DEBUG) && not defined(ESP32)
353  // The ESP32 I2C interferes with the Ticker / Timer library used.
354  // Even with 100 kHz clock we have some dropouts / NAK's because of sending address again instead of first data.
355  uint8_t tWireReturnCode = mI2CClass->endTransmission();
356  if (tWireReturnCode != 0) {
357  // If you end up here, maybe the second module is not attached?
358  Serial.print((char) (tWireReturnCode + '0')); // Error enum i2c_err_t: I2C_ERROR_ACK = 2, I2C_ERROR_TIMEOUT = 3
359  }
360 # else
361  mI2CClass->endTransmission();
362 # endif
363 #endif
364 }
365 
373 void ServoEasing::setPWM(uint16_t aPWMOnStartValueAsUnits, uint16_t aPWMPulseDurationAsUnits) {
374 #if defined(USE_SOFT_I2C_MASTER)
375  i2c_start(mPCA9685I2CAddress << 1);
376  i2c_write((PCA9685_FIRST_PWM_REGISTER) + 4 * mServoPin);
377  i2c_write(aPWMOnStartValueAsUnits);
378  i2c_write(aPWMOnStartValueAsUnits >> 8);
379  i2c_write(aPWMOnStartValueAsUnits + aPWMPulseDurationAsUnits);
380  i2c_write((aPWMOnStartValueAsUnits + aPWMPulseDurationAsUnits) >> 8);
381  i2c_stop();
382 #else
383  mI2CClass->beginTransmission(mPCA9685I2CAddress);
384  mI2CClass->write((PCA9685_FIRST_PWM_REGISTER) + 4 * mServoPin);
385  mI2CClass->write(aPWMOnStartValueAsUnits);
386  mI2CClass->write(aPWMOnStartValueAsUnits >> 8);
387  mI2CClass->write(aPWMOnStartValueAsUnits + aPWMPulseDurationAsUnits);
388  mI2CClass->write((aPWMOnStartValueAsUnits + aPWMPulseDurationAsUnits) >> 8);
389 # if defined(LOCAL_DEBUG) && not defined(ESP32)
390  // The ESP32 I2C interferes with the Ticker / Timer library used.
391  // Even with 100 kHz clock we have some dropouts / NAK's because of sending address again instead of first data.
392  uint8_t tWireReturnCode = mI2CClass->endTransmission(); // blocking call
393  if (tWireReturnCode != 0) {
394  // If you end up here, maybe the second module is not attached?
395  Serial.print((char) (tWireReturnCode + '0')); // Error enum i2c_err_t: I2C_ERROR_ACK = 2, I2C_ERROR_TIMEOUT = 3
396  }
397 # else
398  mI2CClass->endTransmission();
399 # endif
400 #endif
401 }
402 
403 int ServoEasing::MicrosecondsToPCA9685Units(int aMicroseconds) {
404  /*
405  * 4096 units per 20 milliseconds => aMicroseconds / 4.8828
406  */
407 #if defined(USE_SERVO_LIB)
408  if (!mServoIsConnectedToExpander) {
409  return aMicroseconds; // we must return microseconds here
410  }
411 #endif
412  return ((4096L * aMicroseconds) / SERVO_REFRESH_INTERVAL_MICROS);
413 }
414 
415 int ServoEasing::PCA9685UnitsToMicroseconds(int aPCA9685Units) {
416  /*
417  * 4096 units per 20 milliseconds => aPCA9685Units * 4.8828
418  * (aPCA9685Units * 625) / 128 use int32_t to avoid overflow
419  */
420  return ((int32_t) aPCA9685Units * (SERVO_REFRESH_INTERVAL_MICROS / 32)) / (4096 / 32);
421 }
422 
423 #endif // defined(USE_PCA9685_SERVO_EXPANDER)
424 
425 // Constructor without I2C address
426 ServoEasing::ServoEasing() // @suppress("Class members should be properly initialized")
427 #if (!defined(USE_PCA9685_SERVO_EXPANDER) || defined(USE_SERVO_LIB)) && !defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
428 :
429  Servo()
430 #endif
431 {
432  // On an ESP8266 it was NOT initialized to 0 :-(.
434  mServoMoves = false;
435 #if !defined(DISABLE_PAUSE_RESUME)
436  mServoIsPaused = false;
437 #endif
438 
439 #if defined(USE_PCA9685_SERVO_EXPANDER) && defined(USE_SERVO_LIB)
440  mServoIsConnectedToExpander = false;
441 #endif
442 #if !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
444 # if defined(ENABLE_EASE_USER)
445  mUserEaseInFunction = nullptr;
446 # endif
447 #endif
449 
450 #if defined(ENABLE_MIN_AND_MAX_CONSTRAINTS)
451  // initialize with some reasonable values
452  mMinMicrosecondsOrUnits = DEFAULT_MICROSECONDS_FOR_0_DEGREE / 2;
454 #endif
455 
456 #if defined(MEASURE_SERVO_EASING_INTERRUPT_TIMING)
457  pinMode(TIMING_OUTPUT_PIN, OUTPUT);
458 #endif
459 }
460 
473 uint8_t ServoEasing::attach(int aPin) {
475 }
476 
477 // Here no units accepted, only microseconds!
478 uint8_t ServoEasing::attach(int aPin, int aMicrosecondsForServo0Degree, int aMicrosecondsForServo180Degree) {
479  return attach(aPin, aMicrosecondsForServo0Degree, aMicrosecondsForServo180Degree, 0, 180);
480 }
481 
485 uint8_t ServoEasing::attach(int aPin, int aInitialDegreeOrMicrosecond) {
486  return attach(aPin, aInitialDegreeOrMicrosecond, DEFAULT_MICROSECONDS_FOR_0_DEGREE, DEFAULT_MICROSECONDS_FOR_180_DEGREE);
487 }
488 
492 uint8_t ServoEasing::attachWithTrim(int aPin, int aTrimDegreeOrMicrosecond, int aInitialDegreeOrMicrosecond) {
493  return attachWithTrim(aPin, aTrimDegreeOrMicrosecond, aInitialDegreeOrMicrosecond, DEFAULT_MICROSECONDS_FOR_0_DEGREE,
495 }
496 
504 uint8_t ServoEasing::attach(int aPin, int aInitialDegreeOrMicrosecond, int aMicrosecondsForServo0Degree,
505  int aMicrosecondsForServo180Degree) {
506  return attach(aPin, aInitialDegreeOrMicrosecond, aMicrosecondsForServo0Degree, aMicrosecondsForServo180Degree, 0, 180);
507 }
508 
509 uint8_t ServoEasing::attachWithTrim(int aPin, int aTrimDegreeOrMicrosecond, int aInitialDegreeOrMicrosecond,
510  int aMicrosecondsForServo0Degree, int aMicrosecondsForServo180Degree) {
511  return attachWithTrim(aPin, aTrimDegreeOrMicrosecond, aInitialDegreeOrMicrosecond, aMicrosecondsForServo0Degree,
512  aMicrosecondsForServo180Degree, 0, 180);
513 }
514 
521 uint8_t ServoEasing::attach(int aPin, int aInitialDegreeOrMicrosecond, int aMicrosecondsForServoLowDegree,
522  int aMicrosecondsForServoHighDegree, int aServoLowDegree, int aServoHighDegree) {
523  uint8_t tReturnValue = attach(aPin, aMicrosecondsForServoLowDegree, aMicrosecondsForServoHighDegree, aServoLowDegree,
524  aServoHighDegree);
525  write(aInitialDegreeOrMicrosecond);
526  return tReturnValue;
527 }
528 
529 uint8_t ServoEasing::attachWithTrim(int aPin, int aTrimDegreeOrMicrosecond, int aInitialDegreeOrMicrosecond,
530  int aMicrosecondsForServoLowDegree, int aMicrosecondsForServoHighDegree, int aServoLowDegree, int aServoHighDegree) {
531  uint8_t tReturnValue = attach(aPin, aMicrosecondsForServoLowDegree, aMicrosecondsForServoHighDegree, aServoLowDegree,
532  aServoHighDegree);
533  /*
534  * Trim value was reset by attach.
535  * Do not write here, because we need conversion of aInitialDegreeOrMicrosecond, which is included in write() :-).
536  */
537  setTrim(aTrimDegreeOrMicrosecond, false);
538  write(aInitialDegreeOrMicrosecond);
539  return tReturnValue;
540 }
541 
542 /*
543  * Like attach, but keep end position values e.g. of last attach().
544  * !!! Can only be used AFTER initial attach() and detach()!!!
545  * Can be used to reverse / undo a detach() operation
546  */
548  /*
549  * Just put this servo instance into list of servos at first free position
550  */
551  mServoIndex = INVALID_SERVO; // flag indicating an invalid servo index
552  for (uint_fast8_t tServoIndex = 0; tServoIndex < MAX_EASING_SERVOS; ++tServoIndex) {
553  if (ServoEasingArray[tServoIndex] == nullptr) {
554  ServoEasingArray[tServoIndex] = this;
555  mServoIndex = tServoIndex;
556  if (sServoArrayMaxIndex < tServoIndex) {
557  sServoArrayMaxIndex = tServoIndex;
558  }
559  break;
560  }
561  }
562 
563 #if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
564  checkAndInitLightweightServoPin(mServoPin);
565  return mServoPin;
566 #else // We have no Servo::attach for USE_LIGHTWEIGHT_SERVO_LIBRARY
567  // No actions for PCA9685 required
568 # if !defined(USE_PCA9685_SERVO_EXPANDER) || defined(USE_SERVO_LIB)
569  /*
570  * Call attach() of the underlying Servo library and position to the position at the time of detach()
571  */
572 # if defined(ARDUINO_ARCH_APOLLO3)
574  _writeMicrosecondsOrUnits (mLastTargetMicrosecondsOrUnits); // Start at the position at the time of detach()
575  return mServoPin; // Sparkfun apollo3 Servo library has no return value for attach :-(
576 # else
578  _writeMicrosecondsOrUnits(mLastTargetMicrosecondsOrUnits); // Start at the position at the time of detach()
579  return tReturnValue;
580 # endif // defined(ARDUINO_ARCH_APOLLO3)
581 # else
582  return mServoIndex;
583 # endif // defined(USE_SERVO_LIB)
584 #endif // defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
585 }
586 
598 uint8_t ServoEasing::attach(int aPin, int aMicrosecondsForServoLowDegree, int aMicrosecondsForServoHighDegree, int aServoLowDegree,
599  int aServoHighDegree) {
600 
601  /*
602  * Reset trim and reverse
603  */
605  mOperateServoReverse = false;
606 
607  /*
608  * Get the 0 and 180 degree values.
609  */
610  int tMicrosecondsForServo0Degree = map(0, aServoLowDegree, aServoHighDegree, aMicrosecondsForServoLowDegree,
611  aMicrosecondsForServoHighDegree);
612  int tMicrosecondsForServo180Degree = map(180, aServoLowDegree, aServoHighDegree, aMicrosecondsForServoLowDegree,
613  aMicrosecondsForServoHighDegree);
614 
615  mServoPin = aPin;
616 #if defined(USE_PCA9685_SERVO_EXPANDER)
617 # if defined(USE_SERVO_LIB)
618  if (mServoIsConnectedToExpander) {
619  // set units
620  mServo0DegreeMicrosecondsOrUnits = MicrosecondsToPCA9685Units(tMicrosecondsForServo0Degree);
621  mServo180DegreeMicrosecondsOrUnits = MicrosecondsToPCA9685Units(tMicrosecondsForServo180Degree);
622  } else {
623  // set microseconds
624  mServo0DegreeMicrosecondsOrUnits = tMicrosecondsForServo0Degree;
625  mServo180DegreeMicrosecondsOrUnits = tMicrosecondsForServo180Degree;
626  }
627 # else
628  // set units
629  mServo0DegreeMicrosecondsOrUnits = MicrosecondsToPCA9685Units(tMicrosecondsForServo0Degree);
630  mServo180DegreeMicrosecondsOrUnits = MicrosecondsToPCA9685Units(tMicrosecondsForServo180Degree);
631 # endif
632 #else
633  // set microseconds
634  mServo0DegreeMicrosecondsOrUnits = tMicrosecondsForServo0Degree;
635  mServo180DegreeMicrosecondsOrUnits = tMicrosecondsForServo180Degree;
636 #endif
637 
638  /*
639  * Now put this servo instance into list of servos
640  */
641  mServoIndex = INVALID_SERVO; // flag indicating an invalid servo index
642  for (uint_fast8_t tServoIndex = 0; tServoIndex < MAX_EASING_SERVOS; ++tServoIndex) {
643  if (ServoEasingArray[tServoIndex] == nullptr) {
644  ServoEasingArray[tServoIndex] = this;
645  mServoIndex = tServoIndex;
646  if (sServoArrayMaxIndex < tServoIndex) {
647  sServoArrayMaxIndex = tServoIndex;
648  }
649  break;
650  }
651  }
652 
653 #if defined(LOCAL_TRACE)
654  Serial.print("Index=");
655  Serial.print(mServoIndex);
656  Serial.print(" pin=");
657  Serial.print(mServoPin);
658  Serial.print(" low=");
659  Serial.print(aServoLowDegree);
660  Serial.print('|');
661  Serial.print(aMicrosecondsForServoLowDegree);
662  Serial.print(" high=");
663  Serial.print(aServoHighDegree);
664  Serial.print('|');
665  Serial.print(aMicrosecondsForServoHighDegree);
666  Serial.print(' ');
667  printStatic(&Serial);
668 #endif
669  // This error value has priority over the regular return value from Servo::attach()
670  if (mServoIndex == INVALID_SERVO) {
671  return INVALID_SERVO;
672  }
673 
674 #if defined(USE_PCA9685_SERVO_EXPANDER)
675  mLastTargetMicrosecondsOrUnits = DEFAULT_PCA9685_UNITS_FOR_90_DEGREE; // The start value if we forget the initial write()
676 # if defined(USE_SERVO_LIB)
677  if (mServoIsConnectedToExpander) {
678  if (mServoIndex == 0) {
679  I2CInit(); // init only once
680  PCA9685Reset(); // reset only once
681  }
682  PCA9685Init(); // initialize at every attach is simpler but initializing once for every board would be sufficient.
683  return mServoIndex;
684  }
685 # else
686  if (mServoIndex == 0) {
687  I2CInit(); // init only once
688  PCA9685Reset(); // reset only once
689  }
690  PCA9685Init(); // initialize at every attach is simpler but initializing once for every board would be sufficient.
691  return mServoIndex;
692 # endif
693 #endif // defined(USE_PCA9685_SERVO_EXPANDER)
694 
695 #if !defined(USE_PCA9685_SERVO_EXPANDER) || defined(USE_SERVO_LIB)
696  /*
697  * Here servo is NOT connected to expander
698  */
699  mLastTargetMicrosecondsOrUnits = DEFAULT_PULSE_WIDTH; // The start value if we forget the initial write() after attach()
700 
701 # if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
702  if (aPin != LIGHTWEIGHT_SERVO_CHANNEL_A_PIN && aPin != LIGHTWEIGHT_SERVO_CHANNEL_B_PIN
703 #if defined(LIGHTWEIGHT_SERVO_CHANNEL_C_PIN)
704  && aPin != LIGHTWEIGHT_SERVO_CHANNEL_C_PIN
705 #endif
706  ) {
707  return false;
708  }
709  return aPin;
710 # else
711  /*
712  * Use standard arduino servo library
713  * Call attach() of the underlying Servo library
714  */
715 # if defined(ARDUINO_ARCH_APOLLO3)
717  return aPin; // Sparkfun apollo3 Servo library has no return value for attach :-(
718 # else
719  return Servo::attach(aPin, MINIMUM_PULSE_WIDTH, MAXIMUM_PULSE_WIDTH); // This starts generating pulses of DEFAULT_PULSE_WIDTH
720 # endif // defined(ARDUINO_ARCH_APOLLO3)
721 # endif // defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
722 #endif // defined(USE_SERVO_LIB)
723 }
724 
731  if (mServoIndex != INVALID_SERVO) { // check if attached
732  ServoEasingArray[mServoIndex] = nullptr;
733  // If servo with highest index in array was detached, we need to find new sServoArrayMaxIndex
734  while (ServoEasingArray[sServoArrayMaxIndex] == nullptr && sServoArrayMaxIndex > 0) {
736  }
737 
738 #if defined(USE_PCA9685_SERVO_EXPANDER)
739 # if defined(USE_SERVO_LIB)
740  if (mServoIsConnectedToExpander) {
741  setPWM(0); // set signal fully off
742  } else {
743 # if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
744  deinitLightweightServoPin(mServoPin); // disable output and change to input
745 # else
746  Servo::detach();
747 # endif
748  }
749 # else
750  setPWM(0); // set signal fully off
751 # endif // defined(USE_SERVO_LIB)
752 
753 #else
754 # if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
755  deinitLightweightServoPin(mServoPin);
756 # else
757  Servo::detach();
758 # endif
759 #endif // defined(USE_PCA9685_SERVO_EXPANDER)
760  }
761  mServoMoves = false; // safety net to enable right update handling if accidentally called
763 }
764 
771 void ServoEasing::setReverseOperation(bool aOperateServoReverse) {
772  mOperateServoReverse = aOperateServoReverse;
773 }
774 
775 uint_fast16_t ServoEasing::getSpeed() {
776  return mSpeed;
777 }
778 
779 void ServoEasing::setSpeed(uint_fast16_t aDegreesPerSecond) {
780  mSpeed = aDegreesPerSecond;
781 }
782 
789 void ServoEasing::setTrim(int aTrimDegreeOrMicrosecond, bool aDoWrite) {
790  if (aTrimDegreeOrMicrosecond >= 0) {
792  DegreeOrMicrosecondToMicrosecondsOrUnits(aTrimDegreeOrMicrosecond) - mServo0DegreeMicrosecondsOrUnits, aDoWrite);
793  } else {
796  aDoWrite);
797  }
798 }
799 
807 void ServoEasing::_setTrimMicrosecondsOrUnits(int aTrimMicrosecondsOrUnits, bool aDoWrite) {
808  mTrimMicrosecondsOrUnits = aTrimMicrosecondsOrUnits;
809 #if defined(LOCAL_DEBUG)
810  Serial.print(F("Set trim to "));
811  Serial.println(aTrimMicrosecondsOrUnits);
812 #endif
813 #if defined(ENABLE_MIN_AND_MAX_CONSTRAINTS)
814  mMaxMicrosecondsOrUnits -= aTrimMicrosecondsOrUnits;
815  mMinMicrosecondsOrUnits -= aTrimMicrosecondsOrUnits;
816 #endif
817  if (aDoWrite) {
819  }
820 }
821 
822 #if defined(ENABLE_MIN_AND_MAX_CONSTRAINTS)
823 void ServoEasing::setMaxConstraint(int aMaxDegreeOrMicrosecond) {
824  mMaxMicrosecondsOrUnits = DegreeOrMicrosecondToMicrosecondsOrUnits(aMaxDegreeOrMicrosecond);
825 }
826 void ServoEasing::setMinConstraint(int aMinDegreeOrMicrosecond) {
827  mMinMicrosecondsOrUnits = DegreeOrMicrosecondToMicrosecondsOrUnits(aMinDegreeOrMicrosecond);
828 }
829 void ServoEasing::setMinMaxConstraint(int aMinDegreeOrMicrosecond, int aMaxDegreeOrMicrosecond) {
830  mMinMicrosecondsOrUnits = DegreeOrMicrosecondToMicrosecondsOrUnits(aMinDegreeOrMicrosecond);
831  mMaxMicrosecondsOrUnits = DegreeOrMicrosecondToMicrosecondsOrUnits(aMaxDegreeOrMicrosecond);
832 }
833 #endif
834 
835 #if !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
836 void ServoEasing::setEasingType(uint_fast8_t aEasingType) {
837  mEasingType = aEasingType;
838 }
839 
841  return (mEasingType);
842 }
843 
844 # if defined(ENABLE_EASE_USER)
845 void ServoEasing::registerUserEaseInFunction(float (*aUserEaseInFunction)(float aFactorOfTimeCompletion, void *aUserDataPointer),
846  void *aUserDataPointer) {
847  mUserEaseInFunction = aUserEaseInFunction;
848  UserDataPointer = aUserDataPointer;
849 }
850 void ServoEasing::setUserDataPointer(void *aUserDataPointer) {
851  UserDataPointer = aUserDataPointer;
852 }
853 # endif
854 #endif // !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
855 
860 void ServoEasing::write(int aTargetDegreeOrMicrosecond) {
861 #if defined(LOCAL_TRACE)
862  Serial.print(F("write "));
863  Serial.print(aTargetDegreeOrMicrosecond);
864  Serial.print(F(" | "));
865 #endif
866  /*
867  * Check for valid initialization of servo.
868  */
869  if (mServoIndex == INVALID_SERVO) {
870 #if defined(LOCAL_TRACE)
871  Serial.print(F("Error: detached servo"));
872 #endif
873  return;
874  }
875  ServoEasingNextPositionArray[mServoIndex] = aTargetDegreeOrMicrosecond;
877 }
878 
879 void ServoEasing::write(float aTargetDegreeOrMicrosecond) {
880 #if defined(LOCAL_TRACE)
881  Serial.print(F("write "));
882  Serial.print(aTargetDegreeOrMicrosecond);
883  Serial.print(F(" | "));
884 #endif
885  /*
886  * Check for valid initialization of servo.
887  */
888  if (mServoIndex == INVALID_SERVO) {
889 #if defined(LOCAL_TRACE)
890  Serial.print(F("Error: detached servo"));
891 #endif
892  return;
893  }
894  ServoEasingNextPositionArray[mServoIndex] = aTargetDegreeOrMicrosecond;
896 }
897 
902 void ServoEasing::_writeMicrosecondsOrUnits(int aTargetMicrosecondsOrUnits) {
903  /*
904  * Check for valid initialization of servo.
905  */
906  if (mServoIndex == INVALID_SERVO) {
907 #if defined(LOCAL_TRACE)
908  Serial.print(F("Error: detached servo"));
909 #endif
910  return;
911  }
912 #if defined(ENABLE_MIN_AND_MAX_CONSTRAINTS)
913  if (aTargetMicrosecondsOrUnits > mMaxMicrosecondsOrUnits) {
914 #if defined(LOCAL_TRACE)
915  Serial.print(aTargetMicrosecondsOrUnits);
916  Serial.print(F(" > "));
917  Serial.print(mMaxMicrosecondsOrUnits);
918  Serial.print(F(" | "));
919 #endif
920  aTargetMicrosecondsOrUnits = mMaxMicrosecondsOrUnits;
921  } else if (aTargetMicrosecondsOrUnits < mMinMicrosecondsOrUnits) {
922 #if defined(LOCAL_TRACE)
923  Serial.print(aTargetMicrosecondsOrUnits);
924  Serial.print(F(" < "));
925  Serial.print(mMinMicrosecondsOrUnits);
926  Serial.print(F(" | "));
927 #endif
928  aTargetMicrosecondsOrUnits = mMinMicrosecondsOrUnits;
929  }
930 #endif
931  mLastTargetMicrosecondsOrUnits = aTargetMicrosecondsOrUnits;
932 
933 #if defined(LOCAL_TRACE)
934  Serial.print(mServoIndex);
935  Serial.print('/');
936  Serial.print(mServoPin);
937  Serial.print(F(" us/u="));
938  Serial.print(aTargetMicrosecondsOrUnits);
939  if (mTrimMicrosecondsOrUnits != 0) {
940  Serial.print(" +trim=");
941  Serial.print(aTargetMicrosecondsOrUnits + mTrimMicrosecondsOrUnits);
942  }
943 #endif // TRACE
944 
945  /*
946  * Trim added - this is the only place mTrimMicrosecondsOrUnits is evaluated
947  */
948  aTargetMicrosecondsOrUnits += mTrimMicrosecondsOrUnits;
949  /*
950  * Reverse applied, values for 0 to 180 are swapped if reverse - this is the only place mOperateServoReverse is evaluated
951  * (except in the DegreeToMicrosecondsOrUnitsWithTrimAndReverse() function for external testing purposes)
952  */
953  if (mOperateServoReverse) {
954  aTargetMicrosecondsOrUnits = mServo180DegreeMicrosecondsOrUnits
955  - (aTargetMicrosecondsOrUnits - mServo0DegreeMicrosecondsOrUnits);
956 #if defined(LOCAL_TRACE)
957  Serial.print(F(" +reverse="));
958  Serial.print(aTargetMicrosecondsOrUnits);
959 #endif
960  }
961 
962 #if defined(PRINT_FOR_SERIAL_PLOTTER) && !defined(LOCAL_TRACE)
963  Serial.print(' '); // leading separator to separate multiple servo values
964  Serial.print(aTargetMicrosecondsOrUnits);
965 #endif
966 
967 #if defined(USE_PCA9685_SERVO_EXPANDER)
968 # if defined(LOCAL_TRACE)
969  // For each pin show PWM on value used below
970  Serial.print(F(" s="));
971  Serial.print(mServoPin * (4096 - (DEFAULT_PCA9685_UNITS_FOR_180_DEGREE + 100)) / 15); // mServoPin * 233
972 # endif
973 # if defined(USE_SERVO_LIB)
974  if (mServoIsConnectedToExpander) {
975  setPWM(mServoPin * ((4096 - (DEFAULT_PCA9685_UNITS_FOR_180_DEGREE + 100)) / 15), aTargetMicrosecondsOrUnits); // First parameter is: mServoPin * 233
976  } else {
977 # if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
978  writeMicrosecondsLightweightServo(aTargetMicrosecondsOrUnits, (mServoPin == LIGHTWEIGHT_SERVO_CHANNEL_A_PIN));
979 # else
980  Servo::writeMicroseconds(aTargetMicrosecondsOrUnits); // requires 7 us
981 # endif
982  }
983 # else
984  /*
985  * Distribute the servo start time over the 20 ms period.
986  * Unexpectedly this even saves 20 bytes Flash for an ATmega328P
987  */
988  setPWM(mServoPin * ((4096 - (DEFAULT_PCA9685_UNITS_FOR_180_DEGREE + 100)) / 15), aTargetMicrosecondsOrUnits); // mServoPin * 233
989 # endif
990 
991 #else
992 # if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
993  writeMicrosecondsLightweightServoPin(aTargetMicrosecondsOrUnits, mServoPin);
994 # else
995  Servo::writeMicroseconds(aTargetMicrosecondsOrUnits); // requires 7 us on Uno
996 # endif
997 #endif
998 
999 #if defined(LOCAL_TRACE) && !defined(PRINT_FOR_SERIAL_PLOTTER)
1000  Serial.println(); // no newline here, if serial plotter output is requested
1001 #endif
1002 }
1003 
1009 int ServoEasing::MicrosecondsToDegree(int aMicroseconds) {
1010 #if defined(USE_PCA9685_SERVO_EXPANDER)
1011 # if defined(USE_SERVO_LIB)
1012  if (!mServoIsConnectedToExpander) {
1013  return MicrosecondsOrUnitsToDegree(aMicroseconds); // not connected to PCA9685 here
1014  }
1015 # endif
1016  int32_t tResult = aMicroseconds - PCA9685UnitsToMicroseconds(mServo0DegreeMicrosecondsOrUnits);
1017  tResult = (tResult * 180) + 928;
1018  return (tResult / PCA9685UnitsToMicroseconds((mServo180DegreeMicrosecondsOrUnits - mServo0DegreeMicrosecondsOrUnits)));
1019 #else
1020  return MicrosecondsOrUnitsToDegree(aMicroseconds);
1021 #endif
1022 }
1023 
1029 int ServoEasing::MicrosecondsOrUnitsToDegree(int aMicrosecondsOrUnits) {
1039  /*
1040  * compute map with rounding
1041  */
1042 // remove zero degree offset
1043  int32_t tResult = aMicrosecondsOrUnits - mServo0DegreeMicrosecondsOrUnits;
1044 #if defined(USE_PCA9685_SERVO_EXPANDER)
1045 # if defined(USE_SERVO_LIB)
1046  if (mServoIsConnectedToExpander) {
1047  // here we have PCA9685 units
1048  tResult = (tResult * 180) + 190;
1049  } else {
1050  // here we deal with microseconds
1051  tResult = (tResult * 180) + 928;
1052  }
1053 # else
1054  // here we have PCA9685 units
1055  tResult = (tResult * 180) + 190;
1056 # endif
1057 #else
1058 // here we deal with microseconds
1059  tResult = (tResult * 180) + 928; // 928 is the value for 1/2 degree before scaling; (1856 = 180 - 0 degree micros) / 2
1060 #endif
1061 // scale by 180 degree range (180 - 0 degree micros)
1063 
1064 }
1065 
1066 int ServoEasing::MicrosecondsOrUnitsToMicroseconds(int aMicrosecondsOrUnits) {
1067 #if defined(USE_PCA9685_SERVO_EXPANDER)
1068  return PCA9685UnitsToMicroseconds(aMicrosecondsOrUnits);
1069 #else
1070  return aMicrosecondsOrUnits; // we have microseconds here
1071 #endif
1072 
1073 }
1074 
1081 #if defined(DISABLE_MICROS_AS_DEGREE_PARAMETER)
1082  // Only degrees allowed here
1083  return ((int32_t) (aDegreeOrMicrosecond * (int32_t) (mServo180DegreeMicrosecondsOrUnits - mServo0DegreeMicrosecondsOrUnits))
1085 #else // defined(DISABLE_MICROS_AS_DEGREE_PARAMETER)
1086  if (aDegreeOrMicrosecond <= THRESHOLD_VALUE_FOR_INTERPRETING_VALUE_AS_MICROSECONDS) {
1087  /*
1088  * Here aDegreeOrMicrosecond contains degree
1089  */
1090 // return map(aDegreeOrMicrosecond, 0, 180, mServo0DegreeMicrosecondsOrUnits, mServo180DegreeMicrosecondsOrUnits);
1091  // This is equivalent, because we know 0 and 180, and saves 20 bytes program space and is faster :-)
1092  return ((int32_t) (aDegreeOrMicrosecond * (int32_t) (mServo180DegreeMicrosecondsOrUnits - mServo0DegreeMicrosecondsOrUnits))
1094  } else {
1095  /*
1096  * Here aDegreeOrMicrosecond contains microseconds
1097  */
1098 # if defined(USE_PCA9685_SERVO_EXPANDER)
1099  return MicrosecondsToPCA9685Units(aDegreeOrMicrosecond); // return units here
1100 # else
1101  return aDegreeOrMicrosecond; // return microseconds here
1102 # endif
1103  }
1104 #endif // defined(DISABLE_MICROS_AS_DEGREE_PARAMETER)
1105 }
1106 
1108 // For microseconds and PCA9685 units:
1109 #if defined(DISABLE_MICROS_AS_DEGREE_PARAMETER)
1110  return ((int32_t) (aDegreeOrMicrosecond * ((float) (mServo180DegreeMicrosecondsOrUnits - mServo0DegreeMicrosecondsOrUnits))))
1111  / 180 + mServo0DegreeMicrosecondsOrUnits; // return microseconds here
1112 #else
1113  if (aDegreeOrMicrosecond <= THRESHOLD_VALUE_FOR_INTERPRETING_VALUE_AS_MICROSECONDS) {
1114  /*
1115  * Here aDegreeOrMicrosecond contains degree
1116  */
1117  return ((int32_t) (aDegreeOrMicrosecond * ((float) (mServo180DegreeMicrosecondsOrUnits - mServo0DegreeMicrosecondsOrUnits))))
1118  / 180 + mServo0DegreeMicrosecondsOrUnits; // return microseconds here
1119 
1120  } else {
1121  /*
1122  * Here aDegreeOrMicrosecond contains microseconds
1123  */
1124 # if defined(USE_PCA9685_SERVO_EXPANDER)
1125  return MicrosecondsToPCA9685Units(aDegreeOrMicrosecond); // return units here
1126 # else
1127  return aDegreeOrMicrosecond; // return microseconds here
1128 # endif
1129  }
1130 #endif // defined(DISABLE_MICROS_AS_DEGREE_PARAMETER)
1131 }
1132 
1137 // For microseconds and PCA9685 units:
1138  int tResultValue = map(aDegree, 0, 180, mServo0DegreeMicrosecondsOrUnits, mServo180DegreeMicrosecondsOrUnits);
1139  tResultValue += mTrimMicrosecondsOrUnits;
1140  if (mOperateServoReverse) {
1141  tResultValue = mServo180DegreeMicrosecondsOrUnits - (tResultValue - mServo0DegreeMicrosecondsOrUnits);
1142  }
1143  return tResultValue;
1144 }
1145 
1146 void ServoEasing::easeTo(int aTargetDegreeOrMicrosecond) {
1147  easeTo(aTargetDegreeOrMicrosecond, mSpeed);
1148 }
1149 
1150 void ServoEasing::easeTo(float aTargetDegreeOrMicrosecond) {
1151  easeTo(aTargetDegreeOrMicrosecond, mSpeed);
1152 }
1153 
1159 void ServoEasing::easeTo(int aTargetDegreeOrMicrosecond, uint_fast16_t aDegreesPerSecond) {
1160  startEaseTo(aTargetDegreeOrMicrosecond, aDegreesPerSecond, DO_NOT_START_UPDATE_BY_INTERRUPT); // no interrupts
1161  do {
1162  // First do the delay, then check for update, since we are probably called directly after start and there is nothing to move yet
1163  delay(SERVO_REFRESH_INTERVAL_MILLIS); // 20 ms
1164 #if defined(PRINT_FOR_SERIAL_PLOTTER)
1165  } while (!updateAllServos()); // Update all servos in order to always create a complete plotter data set
1166 #else
1167  } while (!update());
1168 #endif
1169 }
1170 
1171 void ServoEasing::easeTo(float aTargetDegreeOrMicrosecond, uint_fast16_t aDegreesPerSecond) {
1172  startEaseTo(aTargetDegreeOrMicrosecond, aDegreesPerSecond, DO_NOT_START_UPDATE_BY_INTERRUPT); // no interrupts
1173  do {
1174  // First do the delay, then check for update, since we are probably called directly after start and there is nothing to move yet
1175  delay(SERVO_REFRESH_INTERVAL_MILLIS); // 20 ms
1176 #if defined(PRINT_FOR_SERIAL_PLOTTER)
1177  } while (!updateAllServos());
1178 #else
1179  } while (!update());
1180 #endif
1181 }
1182 
1183 void ServoEasing::easeToD(int aTargetDegreeOrMicrosecond, uint_fast16_t aMillisForMove) {
1184  startEaseToD(aTargetDegreeOrMicrosecond, aMillisForMove, DO_NOT_START_UPDATE_BY_INTERRUPT);
1185  do {
1186  delay(SERVO_REFRESH_INTERVAL_MILLIS); // 20 ms
1187 #if defined(PRINT_FOR_SERIAL_PLOTTER)
1188  } while (!updateAllServos());
1189 #else
1190  } while (!update());
1191 #endif
1192 }
1193 
1194 void ServoEasing::easeToD(float aTargetDegreeOrMicrosecond, uint_fast16_t aMillisForMove) {
1195  startEaseToD(aTargetDegreeOrMicrosecond, aMillisForMove, DO_NOT_START_UPDATE_BY_INTERRUPT);
1196  do {
1197  delay(SERVO_REFRESH_INTERVAL_MILLIS); // 20 ms
1198 #if defined(PRINT_FOR_SERIAL_PLOTTER)
1199  } while (!updateAllServos());
1200 #else
1201  } while (!update());
1202 #endif
1203 }
1204 
1205 bool ServoEasing::setEaseTo(unsigned int aTargetDegreeOrMicrosecond) {
1206  return startEaseTo((int) aTargetDegreeOrMicrosecond, mSpeed, DO_NOT_START_UPDATE_BY_INTERRUPT);
1207 }
1208 
1209 bool ServoEasing::setEaseTo(int aTargetDegreeOrMicrosecond) {
1210  return startEaseTo(aTargetDegreeOrMicrosecond, mSpeed, DO_NOT_START_UPDATE_BY_INTERRUPT);
1211 }
1212 
1213 bool ServoEasing::setEaseTo(float aTargetDegreeOrMicrosecond) {
1214  return startEaseTo(aTargetDegreeOrMicrosecond, mSpeed, DO_NOT_START_UPDATE_BY_INTERRUPT);
1215 }
1216 
1221 bool ServoEasing::setEaseTo(int aTargetDegreeOrMicrosecond, uint_fast16_t aDegreesPerSecond) {
1222  return startEaseTo(aTargetDegreeOrMicrosecond, aDegreesPerSecond, DO_NOT_START_UPDATE_BY_INTERRUPT);
1223 }
1224 
1225 bool ServoEasing::setEaseTo(float aTargetDegreeOrMicrosecond, uint_fast16_t aDegreesPerSecond) {
1226  return startEaseTo(aTargetDegreeOrMicrosecond, aDegreesPerSecond, DO_NOT_START_UPDATE_BY_INTERRUPT);
1227 }
1228 
1232 bool ServoEasing::startEaseTo(unsigned int aTargetDegreeOrMicrosecond) {
1233  return startEaseTo((int) aTargetDegreeOrMicrosecond, mSpeed, START_UPDATE_BY_INTERRUPT);
1234 }
1235 bool ServoEasing::startEaseTo(int aTargetDegreeOrMicrosecond) {
1236  return startEaseTo(aTargetDegreeOrMicrosecond, mSpeed, START_UPDATE_BY_INTERRUPT);
1237 }
1238 
1239 bool ServoEasing::startEaseTo(float aTargetDegreeOrMicrosecond) {
1240  return startEaseTo(aTargetDegreeOrMicrosecond, mSpeed, START_UPDATE_BY_INTERRUPT);
1241 }
1242 
1243 bool ServoEasing::startEaseTo(unsigned int aTargetDegreeOrMicrosecond, uint_fast16_t aDegreesPerSecond,
1244  bool aStartUpdateByInterrupt) {
1245  return startEaseTo((int) aTargetDegreeOrMicrosecond, aDegreesPerSecond, aStartUpdateByInterrupt);
1246 }
1247 
1253 bool ServoEasing::startEaseTo(int aTargetDegreeOrMicrosecond, uint_fast16_t aDegreesPerSecond, bool aStartUpdateByInterrupt) {
1254 // return startEaseTo((float) aTargetDegreeOrMicrosecond, aDegreesPerSecond, aStartUpdateByInterrupt); // saves 400 bytes
1255  /*
1256  * Avoid division by 0 below
1257  */
1258  if (aDegreesPerSecond == 0) {
1259 #if defined(LOCAL_DEBUG)
1260  Serial.println(F("Speed is 0 -> set to 1"));
1261 #endif
1262  aDegreesPerSecond = 1;
1263  }
1264 
1265  /*
1266  * Get / convert target degree for computation of duration
1267  */
1268  int tTargetDegree = aTargetDegreeOrMicrosecond;
1269 #if defined(DISABLE_MICROS_AS_DEGREE_PARAMETER)
1270  tTargetDegree = aTargetDegreeOrMicrosecond; // no conversion required here
1271 #else
1272 // Convert aDegreeOrMicrosecond to target degree
1273  if (aTargetDegreeOrMicrosecond > THRESHOLD_VALUE_FOR_INTERPRETING_VALUE_AS_MICROSECONDS) {
1274  tTargetDegree = MicrosecondsToDegree(aTargetDegreeOrMicrosecond);
1275  }
1276 #endif
1277 
1279 
1280  /*
1281  * Compute the MillisForCompleteMove parameter for use of startEaseToD() function
1282  */
1283  uint_fast16_t tMillisForCompleteMove = abs(tTargetDegree - tCurrentDegree) * MILLIS_IN_ONE_SECOND / aDegreesPerSecond;
1284 
1285 // bouncing has double movement, so take double time
1286 #if !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
1288  tMillisForCompleteMove *= 2;
1289  }
1290 #endif
1291 
1292  return startEaseToD(aTargetDegreeOrMicrosecond, tMillisForCompleteMove, aStartUpdateByInterrupt);
1293 }
1294 
1295 bool ServoEasing::startEaseTo(float aTargetDegreeOrMicrosecond, uint_fast16_t aDegreesPerSecond, bool aStartUpdateByInterrupt) {
1296  /*
1297  * Avoid division by 0 below
1298  */
1299  if (aDegreesPerSecond == 0) {
1300 #if defined(LOCAL_DEBUG)
1301  Serial.println(F("Speed is 0 -> set to 1"));
1302 #endif
1303  aDegreesPerSecond = 1;
1304  }
1305 
1306  /*
1307  * Get / convert target degree for computation of duration
1308  * Do this as integer computation, with "less" precision
1309  */
1310  int tTargetDegree = aTargetDegreeOrMicrosecond;
1311 #if defined(DISABLE_MICROS_AS_DEGREE_PARAMETER)
1312  tTargetDegree = aTargetDegreeOrMicrosecond; // no conversion required here
1313 #else
1314 // Convert aDegreeOrMicrosecond to target degree
1315  if (aTargetDegreeOrMicrosecond > THRESHOLD_VALUE_FOR_INTERPRETING_VALUE_AS_MICROSECONDS) {
1316  tTargetDegree = MicrosecondsToDegree(aTargetDegreeOrMicrosecond);
1317  }
1318 #endif
1319 
1321 
1322  /*
1323  * Compute the MillisForCompleteMove parameter for use of startEaseToD() function
1324  */
1325  uint_fast16_t tMillisForCompleteMove = abs(tTargetDegree - tCurrentDegree) * MILLIS_IN_ONE_SECOND / aDegreesPerSecond;
1326 
1327 // bouncing has double movement, so take double time
1328 #if !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
1330  tMillisForCompleteMove *= 2;
1331  }
1332 #endif
1333 
1334  return startEaseToD(aTargetDegreeOrMicrosecond, tMillisForCompleteMove, aStartUpdateByInterrupt);
1335 }
1336 
1341 bool ServoEasing::setEaseToD(unsigned int aTargetDegreeOrMicrosecond, uint_fast16_t aMillisForMove) {
1342  return startEaseToD((int) aTargetDegreeOrMicrosecond, aMillisForMove, DO_NOT_START_UPDATE_BY_INTERRUPT);
1343 }
1344 
1345 bool ServoEasing::setEaseToD(int aTargetDegreeOrMicrosecond, uint_fast16_t aMillisForMove) {
1346  return startEaseToD(aTargetDegreeOrMicrosecond, aMillisForMove, DO_NOT_START_UPDATE_BY_INTERRUPT);
1347 }
1348 
1349 bool ServoEasing::setEaseToD(float aTargetDegreeOrMicrosecond, uint_fast16_t aMillisForMove) {
1350  return startEaseToD(aTargetDegreeOrMicrosecond, aMillisForMove, DO_NOT_START_UPDATE_BY_INTERRUPT);
1351 }
1352 
1357 bool ServoEasing::noMovement(uint_fast16_t aMillisToWait) {
1359 }
1360 
1361 bool ServoEasing::startEaseToD(unsigned int aDegreeOrMicrosecond, uint_fast16_t aMillisForMove, bool aStartUpdateByInterrupt) {
1362  return startEaseToD((int) aDegreeOrMicrosecond, aMillisForMove, aStartUpdateByInterrupt);
1363 }
1364 
1370 bool ServoEasing::startEaseToD(int aDegreeOrMicrosecond, uint_fast16_t aMillisForMove, bool aStartUpdateByInterrupt) {
1371  /*
1372  * Check for valid initialization of servo.
1373  */
1374  if (mServoIndex == INVALID_SERVO) {
1375 #if defined(LOCAL_TRACE)
1376  Serial.print(F("Error: detached servo"));
1377 #endif
1378  return true;
1379  }
1380 
1381 #if defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
1382  if (true) {
1383 #else
1384  if (mEasingType != EASE_DUMMY_MOVE) {
1385  // No end position for dummy move. This forces mDeltaMicrosecondsOrUnits to zero, avoiding any movement
1386 #endif
1387  // write the position also to ServoEasingNextPositionArray
1388  ServoEasingNextPositionArray[mServoIndex] = aDegreeOrMicrosecond;
1390  }
1391  int tCurrentMicrosecondsOrUnits = mLastTargetMicrosecondsOrUnits;
1392  mDeltaMicrosecondsOrUnits = mEndMicrosecondsOrUnits - tCurrentMicrosecondsOrUnits;
1393 
1394  mMillisForCompleteMove = aMillisForMove;
1395  mStartMicrosecondsOrUnits = tCurrentMicrosecondsOrUnits;
1396 
1397 #if !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
1399  // bouncing has same end position as start position
1400  mEndMicrosecondsOrUnits = tCurrentMicrosecondsOrUnits;
1401  }
1402 #endif
1403 
1404  mMillisAtStartMove = millis();
1405 
1406 #if defined(LOCAL_TRACE)
1407  printDynamic(&Serial, true);
1408 #elif defined(LOCAL_DEBUG)
1409  printDynamic(&Serial);
1410 #endif
1411 
1412  bool tReturnValue = !mServoMoves;
1413 
1414  mServoMoves = true;
1415 #if !defined(DISABLE_PAUSE_RESUME)
1416  mServoIsPaused = false;
1417 #endif
1418  if (aStartUpdateByInterrupt && !sInterruptsAreActive) {
1420  }
1421 
1422  return tReturnValue;
1423 }
1424 
1425 bool ServoEasing::startEaseToD(float aDegreeOrMicrosecond, uint_fast16_t aMillisForMove, bool aStartUpdateByInterrupt) {
1426  /*
1427  * Check for valid initialization of servo.
1428  */
1429  if (mServoIndex == INVALID_SERVO) {
1430 #if defined(LOCAL_TRACE)
1431  Serial.println(F("Error: detached servo"));
1432 #endif
1433  return true;
1434  }
1435 
1436 #if defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
1437  if (true) {
1438 #else
1439  if (mEasingType != EASE_DUMMY_MOVE) {
1440 #endif
1441  // write the position also to ServoEasingNextPositionArray
1442  ServoEasingNextPositionArray[mServoIndex] = aDegreeOrMicrosecond;
1443  // No end position for dummy move. This forces mDeltaMicrosecondsOrUnits to zero, avoiding any movement
1445  }
1446  int tCurrentMicrosecondsOrUnits = mLastTargetMicrosecondsOrUnits;
1447  mDeltaMicrosecondsOrUnits = mEndMicrosecondsOrUnits - tCurrentMicrosecondsOrUnits;
1448 
1449  mMillisForCompleteMove = aMillisForMove;
1450  mStartMicrosecondsOrUnits = tCurrentMicrosecondsOrUnits;
1451 
1452 #if !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
1454  // bouncing has same end position as start position
1455  mEndMicrosecondsOrUnits = tCurrentMicrosecondsOrUnits;
1456  }
1457 #endif
1458 
1459  mMillisAtStartMove = millis();
1460 
1461 #if defined(LOCAL_TRACE)
1462  printDynamic(&Serial, true);
1463 #elif defined(LOCAL_DEBUG)
1464  printDynamic(&Serial);
1465 #endif
1466 
1467  bool tReturnValue = !mServoMoves;
1468 
1469  // Check after printDynamic() to see the values
1470  mServoMoves = true;
1471 #if !defined(DISABLE_PAUSE_RESUME)
1472  mServoIsPaused = false;
1473 #endif
1474  if (aStartUpdateByInterrupt && !sInterruptsAreActive) {
1476  }
1477 
1478  return tReturnValue;
1479 }
1480 
1485  mServoMoves = false;
1486 #if !defined(ENABLE_EXTERNAL_SERVO_TIMER_HANDLER)
1487  if (!isOneServoMoving()) {
1488  // disable interrupt only if all servos stopped. This enables independent movements of servos with one interrupt handler.
1489  disableServoEasingInterrupt(); // For external handler, this must also be able to be managed externally
1490  }
1491 #endif
1492 }
1493 
1495 #if !defined(DISABLE_PAUSE_RESUME)
1496  mMillisAtStopMove = millis();
1497  mServoIsPaused = true;
1498 #endif
1499 }
1500 
1502 #if !defined(DISABLE_PAUSE_RESUME)
1503  mMillisAtStartMove += millis() - mMillisAtStopMove; // adjust the start time in order to continue the position of the stop() command.
1504  mServoIsPaused = false;
1505 #endif
1507 }
1508 
1510 #if !defined(DISABLE_PAUSE_RESUME)
1511  mMillisAtStartMove += millis() - mMillisAtStopMove; // adjust the start time in order to continue the position of the stop() command.
1512  mServoIsPaused = false;
1513 #endif
1514 }
1515 
1516 void ServoEasing::setTargetPositionReachedHandler(void (*aTargetPositionReachedHandler)(ServoEasing*)) {
1517  TargetPositionReachedHandler = aTargetPositionReachedHandler;
1518 }
1519 
1523 #if defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
1524 bool ServoEasing::update() {
1525 
1526  if (!mServoMoves) {
1527  return true;
1528  }
1529 
1530  uint32_t tMillisSinceStart = millis() - mMillisAtStartMove;
1531  if (tMillisSinceStart >= mMillisForCompleteMove) {
1532  // end of time reached -> write end position and return true
1534  mServoMoves = false;
1535  if(TargetPositionReachedHandler != nullptr){
1536  // Call end callback function
1538  }
1539  return !mServoMoves; // mServoMoves may be changed by callback handler
1540  }
1541  /*
1542  * Use faster non float arithmetic
1543  * Linear movement: new position is: start position + total delta * (millis_done / millis_total aka "percentage of completion")
1544  * 40 us to compute
1545  */
1546  int_fast16_t tNewMicrosecondsOrUnits = mStartMicrosecondsOrUnits
1547  + ((mDeltaMicrosecondsOrUnits * (int32_t) tMillisSinceStart) / mMillisForCompleteMove);
1548  /*
1549  * Write new position only if changed
1550  */
1551  if (tNewMicrosecondsOrUnits != mLastTargetMicrosecondsOrUnits) {
1552  _writeMicrosecondsOrUnits(tNewMicrosecondsOrUnits);
1553  }
1554  return false;
1555 }
1556 
1557 #else // PROVIDE_ONLY_LINEAR_MOVEMENT
1559 
1560 #if defined(LOCAL_TRACE)
1561 // Serial.print('u');
1562 #endif
1563 
1564  if (!mServoMoves) {
1565 # if defined(PRINT_FOR_SERIAL_PLOTTER)
1566  // call it always for serial plotter to output one servo value
1568 # endif
1569  return true;
1570  }
1571 
1572 #if !defined(DISABLE_PAUSE_RESUME)
1573  if (mServoIsPaused) {
1574  return false; // do not really move but still request next update
1575  }
1576 #endif
1577 
1578 #if defined(LOCAL_TRACE)
1579 // Serial.print('p');
1580 #endif
1581 
1582  uint32_t tMillisSinceStart = millis() - mMillisAtStartMove;
1583  if (tMillisSinceStart >= mMillisForCompleteMove) {
1584  // end of time reached -> write end position and return true
1586  mServoMoves = false;
1587  if (TargetPositionReachedHandler != nullptr) {
1588  // Call end callback function
1590  }
1591  return !mServoMoves; // mServoMoves may be changed by callback handler
1592  }
1593 
1594  int tNewMicrosecondsOrUnits;
1595  if (mEasingType == EASE_LINEAR) {
1596  /*
1597  * Use faster non float arithmetic
1598  * Linear movement: new position is: start position + total delta * (millis_done / millis_total aka "percentage of completion")
1599  * 40 us to compute
1600  * Cast to int32 required for mMillisForCompleteMove for 32 bit platforms, otherwise we divide signed by unsigned. Thanks to drifkind.
1601  */
1602  tNewMicrosecondsOrUnits = mStartMicrosecondsOrUnits
1603  + ((mDeltaMicrosecondsOrUnits * (int32_t) tMillisSinceStart) / (int32_t) mMillisForCompleteMove);
1604  } else {
1605  /*
1606  * Non linear movement -> use floats
1607  * Compute tPercentageOfCompletion - from 0.0 to 1.0
1608  * The expected result of easing function is from 0.0 to 1.0
1609  * or from EASE_FUNCTION_MICROSECONDS_INDICATOR_OFFSET for direct microseconds result
1610  */
1611  float tFactorOfTimeCompletion = (float) tMillisSinceStart / (float) mMillisForCompleteMove;
1612  float tFactorOfMovementCompletion = 0.0;
1613 
1614  uint_fast8_t tCallStyle = mEasingType & CALL_STYLE_MASK; // Values are CALL_STYLE_DIRECT, CALL_STYLE_OUT, CALL_STYLE_IN_OUT, CALL_STYLE_BOUNCING_OUT_IN
1615 
1616  if (tCallStyle == CALL_STYLE_DIRECT) { // CALL_STYLE_IN
1617  // Use IN function direct: Call with PercentageOfCompletion | 0.0 to 1.0. FactorOfMovementCompletion is returnValue (from 0.0 to 1.0)
1618  tFactorOfMovementCompletion = callEasingFunction(tFactorOfTimeCompletion);
1619 
1620  } else if (tCallStyle == CALL_STYLE_OUT) {
1621  // Use IN function to generate OUT function: Call with (1 - PercentageOfCompletion) | 1.0 to 0.0. FactorOfMovementCompletion = (1 - returnValue)
1622  tFactorOfMovementCompletion = 1.0 - (callEasingFunction(1.0 - tFactorOfTimeCompletion));
1623 
1624  } else {
1625  if (tFactorOfTimeCompletion <= 0.5) {
1626  if (tCallStyle == CALL_STYLE_IN_OUT) {
1627  // In the first half, call with (2 * PercentageOfCompletion) | 0.0 to 1.0. FactorOfMovementCompletion = (0.5 * returnValue)
1628  tFactorOfMovementCompletion = 0.5 * (callEasingFunction(2.0 * tFactorOfTimeCompletion));
1629  }
1630  if (tCallStyle == CALL_STYLE_BOUNCING_OUT_IN) {
1631  // In the first half, call with (1 - (2 * PercentageOfCompletion)) | 1.0 to 0.0. FactorOfMovementCompletion = (1 - returnValue) -> call OUT 2 times faster.
1632  tFactorOfMovementCompletion = 1.0 - (callEasingFunction(1.0 - (2.0 * tFactorOfTimeCompletion)));
1633  }
1634  } else {
1635  if (tCallStyle == CALL_STYLE_IN_OUT) {
1636  // In the second half, call with (2 - (2 * PercentageOfCompletion)) | 1.0 to 0.0. FactorOfMovementCompletion = ( 1- (0.5 * returnValue))
1637  tFactorOfMovementCompletion = 1.0 - (0.5 * (callEasingFunction(2.0 - (2.0 * tFactorOfTimeCompletion))));
1638  }
1639  if (tCallStyle == CALL_STYLE_BOUNCING_OUT_IN) {
1640  // In the second half, call with ((2 * PercentageOfCompletion) - 1) | 0.0 to 1.0. FactorOfMovementCompletion = (1- returnValue) -> call OUT 2 times faster and backwards.
1641  tFactorOfMovementCompletion = 1.0 - callEasingFunction((2.0 * tFactorOfTimeCompletion) - 1.0);
1642  }
1643  }
1644  }
1645 
1646 #if defined(LOCAL_TRACE)
1647  Serial.print(F("FactorOfTimeCompletion="));
1648  Serial.print(tFactorOfTimeCompletion);
1649  Serial.print(F(" FactorOfMovementCompletion="));
1650  Serial.println(tFactorOfMovementCompletion);
1651 #endif
1652 
1653 #if defined(ENABLE_EASE_USER) || defined(ENABLE_EASE_PRECISION) // Only these two types returns microseconds yet
1654  // Threshold of 400 corresponds to around -14 degree
1655  if (tFactorOfMovementCompletion >= EASE_FUNCTION_MICROSECONDS_INDICATOR_OFFSET) {
1656  // Here we have called an easing function, which returns microseconds or units instead of the factor of completion (0.0 to 1.0)
1657 #if defined(USE_PCA9685_SERVO_EXPANDER)
1658 # if defined(USE_SERVO_LIB)
1659  if (mServoIsConnectedToExpander) {
1660  tNewMicrosecondsOrUnits = MicrosecondsToPCA9685Units(tFactorOfMovementCompletion);
1661  } else {
1662  tNewMicrosecondsOrUnits = tFactorOfMovementCompletion; // not connected to PCA9685 here
1663  }
1664 # else
1665  tNewMicrosecondsOrUnits = MicrosecondsToPCA9685Units(tFactorOfMovementCompletion);
1666 # endif
1667 #else
1668  tNewMicrosecondsOrUnits = tFactorOfMovementCompletion; // get the microseconds delivered by the function
1669 #endif
1670  } else
1671 #endif
1672 #if defined(ENABLE_EASE_USER)
1673  // check for degree values from -180 to 180 (tFactorOfMovementCompletion from 20 to 380)
1674  if (tFactorOfMovementCompletion >= EASE_FUNCTION_DEGREE_THRESHOLD) {
1675  // Here we have called an easing function, which returns degree instead of the factor of completion (0.0 to 1.0)
1676  tNewMicrosecondsOrUnits = DegreeOrMicrosecondToMicrosecondsOrUnits(
1677  (float) (tFactorOfMovementCompletion - EASE_FUNCTION_DEGREE_INDICATOR_OFFSET + 0.5));
1678  } else
1679 #endif
1680  {
1681  int tDeltaMicroseconds = mDeltaMicrosecondsOrUnits * tFactorOfMovementCompletion; // having this as int value saves float operations
1682  tNewMicrosecondsOrUnits = mStartMicrosecondsOrUnits + tDeltaMicroseconds;
1683  }
1684  }
1685 
1686 # if defined(PRINT_FOR_SERIAL_PLOTTER)
1687  // call it always for serial plotter
1688  _writeMicrosecondsOrUnits(tNewMicrosecondsOrUnits);
1689 # else
1690  /*
1691  * Write new position only if changed
1692  */
1693  if (tNewMicrosecondsOrUnits != mLastTargetMicrosecondsOrUnits) {
1694  _writeMicrosecondsOrUnits(tNewMicrosecondsOrUnits);
1695  }
1696 # endif
1697  return false;
1698 }
1699 
1700 float ServoEasing::callEasingFunction(float aFactorOfTimeCompletion) {
1701  uint_fast8_t tEasingType = mEasingType & EASE_TYPE_MASK;
1702 
1703  switch (tEasingType) {
1704 
1705 # if defined(ENABLE_EASE_USER)
1706  case EASE_USER_DIRECT:
1707  if (mUserEaseInFunction != nullptr) {
1708  return mUserEaseInFunction(aFactorOfTimeCompletion, UserDataPointer);
1709  } else {
1710  return 0.0;
1711  }
1712 # endif
1713 
1714 # if defined(ENABLE_EASE_QUADRATIC)
1715  case EASE_QUADRATIC_IN:
1716  return QuadraticEaseIn(aFactorOfTimeCompletion);
1717 # endif
1718 # if defined(ENABLE_EASE_CUBIC)
1719  case EASE_CUBIC_IN:
1720  return CubicEaseIn(aFactorOfTimeCompletion);
1721 # endif
1722 # if defined(ENABLE_EASE_QUARTIC)
1723  case EASE_QUARTIC_IN:
1724  return QuarticEaseIn(aFactorOfTimeCompletion);
1725 # endif
1726 
1727 # if defined(ENABLE_EASE_SINE)
1728  case EASE_SINE_IN:
1729  return SineEaseIn(aFactorOfTimeCompletion);
1730 # endif
1731 # if defined(ENABLE_EASE_CIRCULAR)
1732  case EASE_CIRCULAR_IN:
1733  return CircularEaseIn(aFactorOfTimeCompletion);
1734 # endif
1735 # if defined(ENABLE_EASE_BACK)
1736  case EASE_BACK_IN:
1737  return BackEaseIn(aFactorOfTimeCompletion);
1738 # endif
1739 # if defined(ENABLE_EASE_ELASTIC)
1740  case EASE_ELASTIC_IN:
1741  return ElasticEaseIn(aFactorOfTimeCompletion);
1742 # endif
1743 # if defined(ENABLE_EASE_BOUNCE)
1744  case EASE_BOUNCE_OUT:
1745  return EaseOutBounce(aFactorOfTimeCompletion);
1746 # endif
1747 # if defined(ENABLE_EASE_PRECISION)
1748  case EASE_PRECISION_IN:
1749  return LinearWithQuadraticBounce(aFactorOfTimeCompletion);
1750 # endif
1751  default:
1752  return 0.0;
1753  }
1754 }
1755 
1756 #endif //PROVIDE_ONLY_LINEAR_MOVEMENT
1757 
1762 #if defined(ESP8266)
1763  yield();
1764 #elif defined(ESP32)
1765 // esp_task_wdt_reset();
1766 // yield(); // taskYIELD() and yield() sometimes helps, but this is not deterministic :-(. Allow context switch for the ticker task to run
1767 #endif
1768  return mServoMoves;
1769 }
1770 
1775 #if defined(ESP8266)
1776  yield();
1777 #elif defined(ESP32)
1778 // esp_task_wdt_reset();
1779 // yield(); // Allow context switch for the ticker task to run
1780 #endif
1781  return sInterruptsAreActive;
1782 }
1783 
1792  return isMoving();
1793 }
1794 
1797 }
1798 // To be compatible to Servo library
1800  return getCurrentAngle();
1801 }
1802 
1805 }
1806 // To be compatible to Servo library
1808  return getCurrentMicroseconds();
1809 }
1810 
1812  return mEndMicrosecondsOrUnits;
1813 }
1814 
1820 }
1821 
1824 }
1825 
1827  return mMillisForCompleteMove;
1828 }
1829 
1835 void ServoEasing::print(Print *aSerial, bool doExtendedOutput) {
1836  printDynamic(aSerial, doExtendedOutput);
1837  printStatic(aSerial);
1838 }
1839 
1844 void ServoEasing::printEasingType(Print *aSerial, uint_fast8_t aEasingType) {
1845 # if defined(__AVR__)
1846  const char *tEaseTypeStringPtr = (char*) pgm_read_word(&easeTypeStrings[aEasingType & EASE_TYPE_MASK]);
1847  aSerial->print((__FlashStringHelper*) (tEaseTypeStringPtr));
1848 # else
1849  aSerial->print(easeTypeStrings[aEasingType & EASE_TYPE_MASK]);
1850 # endif
1851  uint_fast8_t tEasingTypeCallStyle = aEasingType & CALL_STYLE_MASK;
1852  if (tEasingTypeCallStyle == CALL_STYLE_IN) {
1853  aSerial->print(F("_in"));
1854  } else if (tEasingTypeCallStyle == CALL_STYLE_OUT) {
1855  aSerial->print(F("_out"));
1856  } else if (tEasingTypeCallStyle == CALL_STYLE_IN_OUT) {
1857  aSerial->print(F("_in_out"));
1858  } else {
1859  aSerial->print(F("_bouncing_in_out"));
1860  }
1861 }
1862 
1864  aTargetMicrosecondsOrUnits += mTrimMicrosecondsOrUnits;
1865  if (mOperateServoReverse) {
1866  aTargetMicrosecondsOrUnits = mServo180DegreeMicrosecondsOrUnits
1867  - (aTargetMicrosecondsOrUnits - mServo0DegreeMicrosecondsOrUnits);
1868  }
1869  return aTargetMicrosecondsOrUnits;
1870 }
1871 
1877 void ServoEasing::printDynamic(Print *aSerial, bool doExtendedOutput) {
1878 // pin is static but it is required for identifying the servo
1879  aSerial->print(mServoIndex);
1880  aSerial->print('/');
1881  aSerial->print(mServoPin);
1882  aSerial->print(F(": "));
1883 
1885  if (doExtendedOutput) {
1886  aSerial->print('|');
1888  }
1889 
1890  aSerial->print(F(" -> "));
1892  if (doExtendedOutput) {
1893  aSerial->print('|');
1895  }
1896 
1897  aSerial->print(F(" = "));
1898  int tDelta;
1899  if (mDeltaMicrosecondsOrUnits >= 0) {
1901  } else {
1903  }
1904  aSerial->print(tDelta);
1905  if (doExtendedOutput) {
1906  aSerial->print('|');
1907  aSerial->print(mDeltaMicrosecondsOrUnits);
1908  }
1909 
1910  aSerial->print(F(" in "));
1911  aSerial->print(mMillisForCompleteMove);
1912  aSerial->print(F(" ms"));
1913 
1914  aSerial->print(F(" with speed="));
1915  aSerial->print(mSpeed);
1916 
1917 #if !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
1918  aSerial->print(F(" and easingType=0x"));
1919  aSerial->print(mEasingType, HEX);
1920  aSerial->print('|');
1921  printEasingType(aSerial, mEasingType);
1922 #endif
1923 
1924  if (doExtendedOutput) {
1925  aSerial->print(F(" MillisAtStartMove="));
1926  aSerial->print(mMillisAtStartMove);
1927  }
1928 
1929  aSerial->println();
1930 }
1931 
1936 void ServoEasing::printStatic(Print *aSerial) {
1937 
1938  aSerial->print(F("0="));
1939  aSerial->print(mServo0DegreeMicrosecondsOrUnits);
1940  aSerial->print(F(" 180="));
1941  aSerial->print(mServo180DegreeMicrosecondsOrUnits);
1942 
1943  aSerial->print(F(" trim="));
1944  if (mTrimMicrosecondsOrUnits >= 0) {
1946  } else {
1948  }
1949  aSerial->print('|');
1950  aSerial->print(mTrimMicrosecondsOrUnits);
1951 
1952  aSerial->print(F(" reverse="));
1953  aSerial->print(mOperateServoReverse);
1954 
1955 #if defined(USE_PCA9685_SERVO_EXPANDER)
1956  aSerial->print(F(" PCA9685I2CAddress=0x"));
1957  aSerial->print(mPCA9685I2CAddress, HEX);
1958 #if !defined(USE_SOFT_I2C_MASTER)
1959  aSerial->print(F(" &Wire=0x"));
1960 // aSerial->print((uintptr_t) mI2CClass, HEX); // defined since C++11
1961  aSerial->print((uint_fast16_t) mI2CClass, HEX);
1962 #endif
1963 
1964 # if defined(USE_SERVO_LIB)
1965  aSerial->print(F(" at expander="));
1966  aSerial->print(mServoIsConnectedToExpander);
1967 # endif
1968 #endif
1969 
1970  aSerial->print(F(" callback=0x"));
1971  aSerial->print((__SIZE_TYPE__) TargetPositionReachedHandler, HEX);
1972 
1973  aSerial->print(F(" MAX_EASING_SERVOS="));
1974  aSerial->print(MAX_EASING_SERVOS);
1975 
1976  aSerial->print(F(" this=0x"));
1977  aSerial->println((uint_fast16_t) this, HEX);
1978 }
1979 
1980 void ServoEasing::printExtra(Print *aSerial) {
1981  aSerial->print(F("ServoArrayMaxIndex="));
1982  aSerial->print(sServoArrayMaxIndex);
1983  aSerial->print(F(" InterruptsAreActive="));
1984  aSerial->println(sInterruptsAreActive);
1985 }
1986 
1991 int clipDegreeSpecial(uint_fast8_t aDegreeToClip) {
1992  if (aDegreeToClip) {
1993  return aDegreeToClip;
1994  }
1995  if (aDegreeToClip < 218) {
1996  return 180;
1997  }
1998  return 0;
1999 }
2000 
2008 #if !defined(ENABLE_EXTERNAL_SERVO_TIMER_HANDLER)
2009 # if defined(STM32F1xx) && STM32_CORE_VERSION_MAJOR == 1 && STM32_CORE_VERSION_MINOR <= 8 // for "Generic STM32F1 series" from STM32 Boards from STM32 cores of Arduino Board manager
2010 void handleServoTimerInterrupt(HardwareTimer *aDummy __attribute__((unused))) // changed in stm32duino 1.9 - 5/2020
2011 #else
2013 # endif
2014 {
2015 # if defined(USE_PCA9685_SERVO_EXPANDER)
2016 // Otherwise it will hang forever in I2C transfer
2017 # if !defined(ARDUINO_ARCH_MBED)
2018  interrupts();
2019 # endif
2020 # endif
2021  if (updateAllServos()) {
2022  // disable interrupt only if all servos stopped. This enables independent movements of servos with this interrupt handler.
2024  }
2025 }
2026 #endif // !defined(ENABLE_EXTERNAL_SERVO_TIMER_HANDLER)
2027 
2028 
2029 #if defined(OCR1B)
2030 
2033 void setTimer1InterruptMarginMicros(uint16_t aInterruptMarginMicros){
2034  // Generate interrupt aInterruptMarginMicros us before a new servo period starts
2035  OCR1B = ((clockCyclesPerMicrosecond() * SERVO_REFRESH_INTERVAL_MICROS) / 8) - aInterruptMarginMicros;
2036 }
2037 #endif
2038 
2039 // The eclipse formatter has problems with // comments in undefined code blocks
2040 // !!! Must be without trailing comment and closed by @formatter:on
2041 // @formatter:off
2049 #if defined(LOCAL_TRACE)
2050  Serial.println(F("enableServoEasingInterrupt"));
2051 #endif
2052 #if defined(__AVR__)
2053 # if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
2054 # if defined(USE_PCA9685_SERVO_EXPANDER) && !defined(USE_SERVO_LIB)
2055 // set timer 5 to 20 ms, since the servo library does not do this for us
2056  TCCR5A = _BV(WGM11);// FastPWM Mode mode TOP (20 ms) determined by ICR1 - non-inverting Compare Output mode OC1A+OC1B
2057  TCCR5B = _BV(WGM13) | _BV(WGM12) | _BV(CS11);// set prescaler to 8, FastPWM mode mode bits WGM13 + WGM12
2058  ICR5 = (F_CPU / 8) / SERVO_REFRESH_FREQUENCY; // 40000 - set period to 50 Hz / 20 ms
2059 # endif
2060 
2061  /*
2062  * TIMER5_COMPA_vect is used by the Servo library, so use TIMER5_COMPC_vect for ServoEasing.
2063  * If USE_LIGHTWEIGHT_SERVO_LIBRARY is enabled, the interrupt time is determined by servo pulse setting for pin 44
2064  * Calling of enableServoEasingInterrupt() disconnects pin 44 to avoid a wrong servo signal
2065  */
2066  TIFR5 |= _BV(OCF5C); // clear any pending interrupts;
2067  TIMSK5 |= _BV(OCIE5C); // enable the output compare B interrupt
2068 # if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
2069  // disable output on pin 44 to avoid a wrong servo signal by setting OCR5C
2070  DDRL &= ~(_BV(DDL5));
2071  TCCR5A &= ~(_BV(COM5C1));
2072 # endif
2073  OCR5C = ((clockCyclesPerMicrosecond() * SERVO_REFRESH_INTERVAL_MICROS) / 8) - 100;// update values 100 us before the new servo period starts
2074 
2075 # elif defined(__AVR_ATmega4808__) || defined(__AVR_ATmega4809__) || defined(__AVR_ATtiny3217__) // Thinary Nano Every with MegaCoreX, Uno WiFi Rev 2, Nano Every, Tiny Core 32 Dev Board
2076  // For MegaTinyCore:
2077  // TCB1 is used by Tone()
2078  // TCB2 is used by Servo, but we cannot hijack the ISR, so we must use a dedicated timer for the 20 ms interrupt
2079  // TCB3 is used by millis()
2080  // Must use TCA0, since TCBx have only prescaler %2. Use single (16bit) mode, because it seems to be easier :-)
2081  TCA0.SINGLE.CTRLD = 0; // Single mode - required at least for MegaTinyCore
2082  TCA0.SINGLE.CTRLB = TCA_SINGLE_WGMODE_NORMAL_gc; // Normal mode, top = PER
2083  TCA0.SINGLE.PER = (((F_CPU / 1000000) * SERVO_REFRESH_INTERVAL_MICROS) / 8); // 40000 at 16 MHz
2084  TCA0.SINGLE.CTRLA = TCA_SINGLE_CLKSEL_DIV8_gc | TCA_SINGLE_ENABLE_bm; // set prescaler to 8 and enable timer
2085  TCA0.SINGLE.INTCTRL = TCA_SINGLE_OVF_bm; // Enable overflow interrupt
2086 
2087 # if defined(MEGACOREX) && defined(USE_TIMERB2)
2088 #error It seems, that not the Megacore Servo library, but an Arduino Servo library is taken for compile, which will lead to errors. You must update MEGACOREX to >= 1.1.1 or remove the Arduino Servo library to fix this.
2089 # endif
2090 # elif defined(TCCR1B) && defined(TIFR1) // Uno, Nano etc.
2091  /*
2092  * Standard AVR
2093  * Use timer 1, together with the servo library, which uses the output compare A interrupt.
2094  * Therefore we use the output compare B interrupt and generate an interrupt 100 microseconds,
2095  * before a new servo period starts. This leaves the first servo signals undisturbed.
2096  */
2097 # if defined(USE_PCA9685_SERVO_EXPANDER) && !defined(USE_SERVO_LIB)
2098 // // set timer 1 to 20 ms, since the servo library or lightweight_servo library does not do this for us
2099  TCCR1A = _BV(WGM11); // FastPWM Mode mode TOP (20 ms) determined by ICR1 - non-inverting Compare Output mode OC1A+OC1B
2100  TCCR1B = _BV(WGM13) | _BV(WGM12) | _BV(CS11); // set prescaler to 8, FastPWM mode mode bits WGM13 + WGM12
2101  ICR1 = (F_CPU / 8) / SERVO_REFRESH_FREQUENCY; // 40000 - set period to 50 Hz / 20 ms
2102 # endif
2103 
2104  TIFR1 |= _BV(OCF1B); // clear any pending interrupts;
2105  TIMSK1 |= _BV(OCIE1B); // enable the output compare B interrupt used by ServoEasing
2106  /*
2107  * Misuse the "Input Capture Noise Canceler Bit" as a flag, that signals that interrupts for ServoEasing are enabled again.
2108  * It is required if disableServoEasingInterrupt() is suppressed e.g. by an overwritten handleServoTimerInterrupt() function
2109  * because the servo interrupt is used to synchronize e.g. NeoPixel updates.
2110  */
2111  TCCR1B |= _BV(ICNC1);
2112 # if !defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
2113  OCR1B = ((clockCyclesPerMicrosecond() * SERVO_REFRESH_INTERVAL_MICROS) / 8) - 100; // Generate interrupt 100 us before a new servo period starts
2114 # endif
2115 
2116 # else
2117 #error "This AVR CPU is not supported by ServoEasing"
2118 # endif
2119 
2120 #elif defined(ESP8266) || defined(ESP32)
2122  Timer20ms.detach(); // otherwise the ESP32 kernel at least will crash and reboot
2123  }
2124  // The callback is called by a RTOS task not an ISR, which allows us to have the callback without the IRAM attribute
2126 
2127 // BluePill in 2 flavors
2128 #elif defined(STM32F1xx) // for "STMicroelectronics:stm32" from STM32 Boards from STM32 cores of Arduino Board manager
2129  Timer20ms.setMode(LL_TIM_CHANNEL_CH1, TIMER_OUTPUT_COMPARE, NC); // used for generating only interrupts, no pin specified
2130  Timer20ms.setOverflow(SERVO_REFRESH_INTERVAL_MICROS, MICROSEC_FORMAT); // microsecond period
2131  Timer20ms.attachInterrupt(handleServoTimerInterrupt); // this sets update interrupt enable
2132  Timer20ms.resume(); // Start or resume HardwareTimer: all channels are resumed, interrupts are enabled if necessary
2133 
2134 #elif defined(__STM32F1__) // for "stm32duino:STM32F1 Generic STM32F103C series" from STM32F1 Boards (Roger Clark STM32duino.com)
2135  Timer20ms.setMode(TIMER_CH1, TIMER_OUTPUT_COMPARE);
2136  Timer20ms.setPeriod(SERVO_REFRESH_INTERVAL_MICROS); // 20000 microsecond period
2137  Timer20ms.attachInterrupt(TIMER_CH1, handleServoTimerInterrupt);
2138  Timer20ms.refresh(); // Set the timer's count to 0 and update the prescaler and overflow values.
2139 
2140 #elif defined(__SAM3X8E__) // Arduino DUE
2141  pmc_set_writeprotect(false);
2142  pmc_enable_periph_clk(ID_TC_FOR_20_MS_TIMER);
2143  NVIC_ClearPendingIRQ(IRQn_FOR_20_MS_TIMER);
2144  NVIC_EnableIRQ(IRQn_FOR_20_MS_TIMER);
2145 
2146  // TIMER_CLOCK3 is MCK/32. MCK is 84MHz Set up the Timer in waveform mode which creates a PWM in UP mode with automatic trigger on RC Compare
2147  TC_Configure(TC_FOR_20_MS_TIMER, CHANNEL_FOR_20_MS_TIMER, TC_CMR_TCCLKS_TIMER_CLOCK3 | TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC);
2148  TC_SetRC(TC_FOR_20_MS_TIMER, CHANNEL_FOR_20_MS_TIMER, (F_CPU / 32) / SERVO_REFRESH_FREQUENCY); // =52500 -> 20ms
2149 
2150  TC_Start(TC_FOR_20_MS_TIMER, CHANNEL_FOR_20_MS_TIMER); // Enables the timer clock stopped by TC_Configure() and performs a software reset to start the counting
2151 
2152  // Enable the RC Compare Interrupt
2153  TC_FOR_20_MS_TIMER->TC_CHANNEL[CHANNEL_FOR_20_MS_TIMER].TC_IER = TC_IER_CPCS;
2154  // Disable all others
2155  TC_FOR_20_MS_TIMER->TC_CHANNEL[CHANNEL_FOR_20_MS_TIMER].TC_IDR = ~TC_IER_CPCS;
2156 
2157 #elif defined(ARDUINO_ARCH_SAMD)
2158  // Servo uses timer 4 and we use timer 5. therefore we cannot change clock source to 32 kHz.
2159 
2160  TcCount16 *TC = (TcCount16*) TC5;
2161 # if defined(__SAMD51__)
2162  // SAMD51 Code initially provided by Lutz
2171  // Enable the TC5 clock, use generic clock generator 0 (F_CPU) for TC5
2172  GCLK->PCHCTRL[TC5_GCLK_ID].reg = GCLK_PCHCTRL_GEN_GCLK0_Val | (1 << GCLK_PCHCTRL_CHEN_Pos);
2173  while (GCLK->SYNCBUSY.reg > 0); // Sync GCLK for TC5
2174 
2175  // The TC should be disabled before the TC is reset in order to avoid undefined behavior.
2176  TC->CTRLA.reg &= ~TC_CTRLA_ENABLE; // Disable the Timer
2177  while (TC->SYNCBUSY.bit.ENABLE); // Wait for disabled
2178  // Reset TCx
2179  TC->CTRLA.reg = TC_CTRLA_SWRST;
2180  // When writing a '1' to the CTRLA.SWRST bit it will immediately read as '1'.
2181  while (TC->SYNCBUSY.bit.SWRST); // CTRL.SWRST will be cleared by hardware when the peripheral has been reset.
2182 
2183  // SAMD51 has F_CPU = 120 MHz
2184  TC->CC[0].reg = ((F_CPU / (256 * SERVO_REFRESH_FREQUENCY)) - 1); // (9375 - 1) at 120 MHz and 256 prescaler. With prescaler 64 we get 37500-1.
2185  /*
2186  * Set timer counter mode to 16 bits, set mode as match frequency, prescaler is DIV256, start counter
2187  */
2188  TC->CTRLA.reg |= TC_CTRLA_MODE_COUNT16 | TC_WAVE_WAVEGEN_MFRQ | TC_CTRLA_PRESCALER_DIV256 | TC_CTRLA_ENABLE;
2189 // while (TC->STATUS.bit.SYNCBUSY == 1); // The next commands do an implicit wait :-)
2190 
2191 # else
2192  // Enable GCLK and select GCLK0 (F_CPU) as clock for TC4 and TC5
2193  GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(GCM_TC4_TC5)); // GCLK0 is F_CPU | 48 MHz
2194 // while (GCLK->STATUS.bit.SYNCBUSY) // not required to wait
2195 // ;
2196 
2197  // The TC should be disabled before the TC is reset in order to avoid undefined behavior.
2198  TC->CTRLA.reg &= ~TC_CTRLA_ENABLE;
2199  // 14.3.2.2 When write-synchronization is ongoing for a register, any subsequent write attempts to this register will be discarded, and an error will be reported.
2200  // 14.3.1.4 It is also possible to perform the next read/write operation and wait,
2201  // as this next operation will be started once the previous write/read operation is synchronized and/or complete. ???
2202  while (TC->STATUS.bit.SYNCBUSY == 1); // wait for sync to ensure that we can write again to COUNT16.CTRLA.reg
2203  // Reset TCx
2204  TC->CTRLA.reg = TC_CTRLA_SWRST;
2205  // When writing a '1' to the CTRLA.SWRST bit it will immediately read as '1'.
2206  while (TC->CTRLA.bit.SWRST); // CTRL.SWRST will be cleared by hardware when the peripheral has been reset.
2207 
2208  TC->CC[0].reg = ((F_CPU / (64 * SERVO_REFRESH_FREQUENCY)) - 1); // (15000 - 1) at 48 Mhz and 64 prescaler.
2209  /*
2210  * Set timer counter mode to 16 bits, set mode as match frequency, prescaler is DIV64 => 750 kHz clock, start counter
2211  */
2212  TC->CTRLA.reg |= TC_CTRLA_MODE_COUNT16| TC_CTRLA_WAVEGEN_MFRQ | TC_CTRLA_PRESCALER_DIV64 | TC_CTRLA_ENABLE;
2213 // while (TC->STATUS.bit.SYNCBUSY == 1); // The next commands do an implicit wait :-)
2214 
2215 # endif // defined(__SAMD51__)
2216  // Common SAMD here
2217  // Configure interrupt request
2218  NVIC_DisableIRQ(TC5_IRQn);
2219  NVIC_ClearPendingIRQ(TC5_IRQn);
2220  NVIC_SetPriority(TC5_IRQn, 0);
2221  NVIC_EnableIRQ(TC5_IRQn);
2222 
2223  // Enable the TC5 interrupt request
2224  TC->INTENSET.bit.MC0 = 1;
2225 // while (TC->STATUS.reg & TC_STATUS_SYNCBUSY) // Not required to wait at end of function
2226 // ; // wait until TC5 is done syncing
2227 
2228 //#elif defined(ARDUINO_ARCH_APOLLO3)
2229 // // use timer 3 segment A
2230 // am_hal_ctimer_clear(3, AM_HAL_CTIMER_TIMERA); // reset timer
2231 // // only AM_HAL_CTIMER_FN_REPEAT resets counter after match (CTC mode)
2232 // am_hal_ctimer_config_single(3, AM_HAL_CTIMER_TIMERA,
2233 // (AM_HAL_CTIMER_INT_ENABLE | AM_HAL_CTIMER_HFRC_12KHZ | AM_HAL_CTIMER_FN_REPEAT));
2234 // am_hal_ctimer_compare_set(3, AM_HAL_CTIMER_TIMERA, 0, 12000 / SERVO_REFRESH_FREQUENCY);
2235 // am_hal_ctimer_start(3, AM_HAL_CTIMER_TIMERA);
2236 //
2237 // am_hal_ctimer_int_register(AM_HAL_CTIMER_INT_TIMERA3, handleServoTimerInterrupt);
2238 // am_hal_ctimer_int_enable(AM_HAL_CTIMER_INT_TIMERA3);
2239 // NVIC_EnableIRQ(CTIMER_IRQn);
2240 
2241 #elif defined(ARDUINO_ARCH_MBED)
2242  Timer20ms.attach(handleServoTimerInterrupt, std::chrono::microseconds(SERVO_REFRESH_INTERVAL_MICROS));
2243 
2244 #elif defined(ARDUINO_ARCH_RP2040)
2245  add_repeating_timer_us(SERVO_REFRESH_INTERVAL_MICROS, handleServoTimerInterruptHelper, nullptr, &Timer20ms);
2246 
2247 #elif defined(TEENSYDUINO)
2248  // common for all Teensy
2250 
2251 #else
2252 #warning Board / CPU is not covered by definitions using pre-processor symbols -> no timer available. Please extend ServoEasing.cpp.
2253 #endif
2255 }
2256 
2258 #if defined(LOCAL_TRACE)
2259  Serial.println(F("disableServoEasingInterrupt"));
2260 #endif
2261 #if defined(__AVR__)
2262 # if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
2263  TIMSK5 &= ~(_BV(OCIE5C)); // disable the output compare C interrupt
2264 
2265 # elif defined(__AVR_ATmega4808__) || defined(__AVR_ATmega4809__) || defined(__AVR_ATtiny3217__) // Thinary Nano Every with MegaCoreX, Uno WiFi Rev 2, Nano Every, Tiny Core 32 Dev Board
2266  TCA0.SINGLE.INTCTRL &= ~(TCA_SINGLE_OVF_bm); // disable the overflow interrupt
2267 
2268 # elif defined(TIMSK1)// defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
2269  TIMSK1 &= ~(_BV(OCIE1B)); // disable the output compare B interrupt
2270 
2271 # else
2272 #error "This AVR CPU is not supported by ServoEasing"
2273 # endif
2274 
2275 #elif defined(ESP8266) || defined(ESP32)
2276  Timer20ms.detach();
2277 
2278 #elif defined(STM32F1xx) // for "Generic STM32F1 series" from STM32 Boards from STM32 cores of Arduino Board manager
2279  // https://github.com/stm32duino/BoardManagerFiles/raw/master/STM32/package_stm_index.json
2280  Timer20ms.setMode(LL_TIM_CHANNEL_CH1, TIMER_DISABLED);
2281  Timer20ms.detachInterrupt();
2282 
2283 #elif defined(__STM32F1__) // for "Generic STM32F103C series" from STM32F1 Boards (STM32duino.com) of Arduino Board manager
2284  // http://dan.drown.org/stm32duino/package_STM32duino_index.json
2285  Timer20ms.setMode(TIMER_CH1, TIMER_DISABLED);
2286  Timer20ms.detachInterrupt(TIMER_CH1);
2287 
2288 #elif defined(__SAM3X8E__) // Arduino DUE
2289  NVIC_DisableIRQ(IRQn_FOR_20_MS_TIMER);
2290 
2291 #elif defined(ARDUINO_ARCH_SAMD)
2292  TC5->COUNT16.CTRLA.reg &= ~TC_CTRLA_ENABLE;
2293 # if defined(__SAMD51__)
2294  while (TC5->COUNT16.STATUS.reg & TC_SYNCBUSY_STATUS); //wait until TC5 is done syncing
2295 # else
2296  while (TC5->COUNT16.STATUS.reg & TC_STATUS_SYNCBUSY); //wait until TC5 is done syncing
2297 # endif
2298 
2299 #elif defined(ARDUINO_ARCH_MBED) // Arduino Nano 33 BLE + Sparkfun Apollo3
2300  Timer20ms.detach();
2301 
2302 #elif defined(ARDUINO_ARCH_RP2040)
2303  cancel_repeating_timer(&Timer20ms);
2304 
2305 //#elif defined(ARDUINO_ARCH_APOLLO3)
2306 // am_hal_ctimer_int_disable(AM_HAL_CTIMER_INT_TIMERA3);
2307 
2308 #elif defined(TEENSYDUINO)
2309  Timer20ms.end();
2310 #endif
2312 }
2313 
2314 // @formatter:on
2320 #if defined(__AVR__)
2321 # if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
2322 ISR(TIMER5_COMPC_vect) {
2324 }
2325 
2326 # elif defined(__AVR_ATmega4808__) || defined(__AVR_ATmega4809__) || defined(__AVR_ATtiny3217__) // Thinary Nano Every with MegaCoreX, Uno WiFi Rev 2, Nano Every, Tiny Core 32 Dev Board
2327 ISR(TCA0_OVF_vect) {
2328  TCA0.SINGLE.INTFLAGS = TCA_SINGLE_OVF_bm; // Reset interrupt flags.
2330 }
2331 
2332 # else // defined(__AVR__)
2333 ISR(TIMER1_COMPB_vect) {
2334 # if defined(MEASURE_SERVO_EASING_INTERRUPT_TIMING)
2335  digitalWriteFast(TIMING_OUTPUT_PIN, HIGH);
2336 # endif
2338 # if defined(MEASURE_SERVO_EASING_INTERRUPT_TIMING)
2339  digitalWriteFast(TIMING_OUTPUT_PIN, LOW);
2340 # endif
2341 }
2342 # endif
2343 
2344 #elif defined(__SAM3X8E__) // Arduino DUE
2345 void HANDLER_FOR_20_MS_TIMER(void) {
2346 # if defined(MEASURE_SERVO_EASING_INTERRUPT_TIMING)
2347  digitalWrite(TIMING_OUTPUT_PIN, HIGH);
2348 # endif
2349  // Clear interrupt
2350  TC_GetStatus(TC_FOR_20_MS_TIMER, CHANNEL_FOR_20_MS_TIMER);//Clear channel status to fire again the interrupt.
2352 # if defined(MEASURE_SERVO_EASING_INTERRUPT_TIMING)
2353  digitalWrite(TIMING_OUTPUT_PIN, LOW);
2354 # endif
2355 }
2356 
2357 #elif defined(ARDUINO_ARCH_SAMD)
2358 void TC5_Handler(void) {
2359 # if defined(MEASURE_SERVO_EASING_INTERRUPT_TIMING)
2360  digitalWrite(TIMING_OUTPUT_PIN, HIGH);
2361 # endif
2362  // Clear interrupt
2363  TC5->COUNT16.INTFLAG.bit.MC0 = 1;
2365 # if defined(MEASURE_SERVO_EASING_INTERRUPT_TIMING)
2366  digitalWrite(TIMING_OUTPUT_PIN, LOW);
2367 # endif
2368 }
2369 
2370 //#elif defined(ARDUINO_ARCH_APOLLO3)
2371 //extern "C" void am_ctimer_isr(void) {
2372 // // Check and clear any active CTIMER interrupts.
2373 // uint32_t ui32Status = am_hal_ctimer_int_status_get(true);
2374 // am_hal_ctimer_int_clear(ui32Status);
2375 //
2376 // // Run handlers for the various possible timer events.
2377 // am_hal_ctimer_int_service(ui32Status);
2378 //}
2379 #endif // defined(__AVR__)
2380 
2381 /************************************
2382  * ServoEasing list functions
2383  ***********************************/
2384 
2385 #if !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
2386 void setEasingTypeForAllServos(uint_fast8_t aEasingType) {
2388 }
2389 
2393 void setEasingTypeForMultipleServos(uint_fast8_t aNumberOfServos, uint_fast8_t aEasingType) {
2394  for (uint_fast8_t tServoIndex = 0; tServoIndex <= aNumberOfServos; ++tServoIndex) {
2395  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr) {
2396  ServoEasing::ServoEasingArray[tServoIndex]->mEasingType = aEasingType;
2397  }
2398  }
2399 }
2400 #endif
2401 
2405 }
2406 
2407 void setEaseToForAllServosSynchronizeAndStartInterrupt(uint_fast16_t aDegreesPerSecond) {
2408  setEaseToForAllServos(aDegreesPerSecond);
2410 }
2411 
2419 }
2420 
2421 void setEaseToForAllServosSynchronizeAndWaitForAllServosToStop(uint_fast16_t aDegreesPerSecond) {
2422  setEaseToForAllServos(aDegreesPerSecond);
2424 }
2425 
2429 }
2430 
2431 void synchronizeAndEaseToArrayPositions(uint_fast16_t aDegreesPerSecond) {
2432  setEaseToForAllServos(aDegreesPerSecond);
2434 }
2435 
2440 void printArrayPositions(Print *aSerial) {
2441 // uint_fast8_t tServoIndex = 0;
2442  aSerial->print(F("ServoNextPositionArray="));
2443 // AJ 22.05.2019 This does not work with GCC 7.3.0 atmel6.3.1 and -Os
2444 // It drops the tServoIndex < MAX_EASING_SERVOS condition, since MAX_EASING_SERVOS is equal to the size of sServoArray
2445 // This has only an effect if the whole sServoArray is filled up, i.e we have declared MAX_EASING_SERVOS ServoEasing objects.
2446 // while (ServoEasing::ServoEasingArray[tServoIndex] != nullptr && tServoIndex < MAX_EASING_SERVOS) {
2447 // aSerial->print(ServoEasingNextPositionArray[tServoIndex]);
2448 // aSerial->print(F(" | "));
2449 // tServoIndex++;
2450 // }
2451 
2452 // switching conditions cures the bug
2453 // while (tServoIndex < MAX_EASING_SERVOS && ServoEasing::ServoEasingArray[tServoIndex] != nullptr) {
2454 
2455 // this also does not work
2456 // for (uint_fast8_t tServoIndex = 0; ServoEasing::ServoEasingArray[tServoIndex] != nullptr && tServoIndex < MAX_EASING_SERVOS ; ++tServoIndex) {
2457 // aSerial->print(ServoEasingNextPositionArray[tServoIndex]);
2458 // aSerial->print(F(" | "));
2459 // }
2460  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2461  aSerial->print(ServoEasing::ServoEasingNextPositionArray[tServoIndex]);
2462  aSerial->print(F(" | "));
2463  }
2464  aSerial->println();
2465 }
2466 
2467 void writeAllServos(int aDegreeOrMicrosecond) {
2468  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2469  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr) {
2470  ServoEasing::ServoEasingArray[tServoIndex]->write(aDegreeOrMicrosecond);
2471  }
2472  }
2473 }
2474 
2475 void setSpeedForAllServos(uint_fast16_t aDegreesPerSecond) {
2476  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2477  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr) {
2478  ServoEasing::ServoEasingArray[tServoIndex]->mSpeed = aDegreesPerSecond;
2479  }
2480  }
2481 }
2482 
2483 #if defined(va_arg)
2484 
2487 void setIntegerDegreeForAllServos(uint_fast8_t aNumberOfServos, va_list *aDegreeValues) {
2488  for (uint_fast8_t tServoIndex = 0; tServoIndex < aNumberOfServos; ++tServoIndex) {
2489  ServoEasing::ServoEasingNextPositionArray[tServoIndex] = va_arg(*aDegreeValues, int);
2490  }
2491 }
2495 void setFloatDegreeForAllServos(uint_fast8_t aNumberOfServos, va_list *aDegreeValues) {
2496  for (uint_fast8_t tServoIndex = 0; tServoIndex < aNumberOfServos; ++tServoIndex) {
2497  ServoEasing::ServoEasingNextPositionArray[tServoIndex] = va_arg(*aDegreeValues, double);
2498  }
2499 }
2500 #endif
2501 
2502 #if defined(va_start)
2503 
2506 void setDegreeForAllServos(uint_fast8_t aNumberOfServos, ...) {
2507  va_list aDegreeValues;
2508  va_start(aDegreeValues, aNumberOfServos);
2509  setIntegerDegreeForAllServos(aNumberOfServos, &aDegreeValues);
2510  va_end(aDegreeValues);
2511 }
2512 
2513 void setIntegerDegreeForAllServos(uint_fast8_t aNumberOfServos, ...) {
2514  va_list aDegreeValues;
2515  va_start(aDegreeValues, aNumberOfServos);
2516  setIntegerDegreeForAllServos(aNumberOfServos, &aDegreeValues);
2517  va_end(aDegreeValues);
2518 }
2522 void setFloatDegreeForAllServos(uint_fast8_t aNumberOfServos, ...) {
2523  va_list aDegreeValues;
2524  va_start(aDegreeValues, aNumberOfServos);
2525  setFloatDegreeForAllServos(aNumberOfServos, &aDegreeValues);
2526  va_end(aDegreeValues);
2527 }
2528 #endif
2529 
2536  bool tOneServoIsMoving = false;
2537  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2538  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr) {
2539  tOneServoIsMoving = ServoEasing::ServoEasingArray[tServoIndex]->setEaseTo(
2541  || tOneServoIsMoving;
2542  }
2543  }
2544  return tOneServoIsMoving;
2545 }
2546 
2552 bool setEaseToForAllServos(uint_fast16_t aDegreesPerSecond) {
2553  bool tOneServoIsMoving = false;
2554  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2555  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr) {
2556  tOneServoIsMoving = ServoEasing::ServoEasingArray[tServoIndex]->setEaseTo(
2557  ServoEasing::ServoEasingNextPositionArray[tServoIndex], aDegreesPerSecond) || tOneServoIsMoving;
2558  }
2559  }
2560  return tOneServoIsMoving;
2561 }
2562 
2568 bool setEaseToDForAllServos(uint_fast16_t aMillisForMove) {
2569  bool tOneServoIsMoving = false;
2570  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2571  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr) {
2572  tOneServoIsMoving = ServoEasing::ServoEasingArray[tServoIndex]->setEaseToD(
2573  ServoEasing::ServoEasingNextPositionArray[tServoIndex], aMillisForMove) || tOneServoIsMoving;
2574  }
2575  }
2576  return tOneServoIsMoving;
2577 }
2578 
2580  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2581  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr && ServoEasing::ServoEasingArray[tServoIndex]->mServoMoves) {
2582  return true;
2583  }
2584  }
2585  return false;
2586 }
2587 
2589  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2590  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr) {
2591  ServoEasing::ServoEasingArray[tServoIndex]->mServoMoves = false;
2592  }
2593  }
2594 #if !defined(ENABLE_EXTERNAL_SERVO_TIMER_HANDLER)
2595  disableServoEasingInterrupt(); // For external handler, this must also be able to be managed externally
2596 #endif
2597 }
2598 
2600 #if !defined(DISABLE_PAUSE_RESUME)
2601  unsigned long tMillis = millis();
2602  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2603  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr) {
2604  ServoEasing::ServoEasingArray[tServoIndex]->mServoIsPaused = true;
2605  ServoEasing::ServoEasingArray[tServoIndex]->mMillisAtStopMove = tMillis;
2606  }
2607  }
2608 #endif
2609 }
2610 
2612  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2613  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr) {
2615  }
2616  }
2617 }
2618 
2620  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2621  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr) {
2623  }
2624  }
2625 }
2626 
2631 #if defined(LOCAL_TRACE)
2632 // Serial.print(F("ua "));
2633 #endif
2634 
2635  bool tAllServosStopped = true;
2636  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2637  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr) {
2638  tAllServosStopped = ServoEasing::ServoEasingArray[tServoIndex]->update() && tAllServosStopped;
2639  }
2640  }
2641 #if defined(PRINT_FOR_SERIAL_PLOTTER)
2642  Serial.println(); // End of one complete data set
2643 #endif
2644  return tAllServosStopped;
2645 }
2646 
2651  do {
2652  // First do the delay, then check for update, since we are probably called directly after start and there is nothing to move yet
2653  delay(SERVO_REFRESH_INTERVAL_MILLIS); // 20 ms
2654  } while (!updateAllServos());
2655 }
2656 
2662 bool delayAndUpdateAndWaitForAllServosToStop(unsigned long aMillisDelay, bool aTerminateDelayIfAllServosStopped) {
2663  while (true) {
2664  // First do the delay, then check for update, since we are probably called directly after start and there is nothing to move yet
2665  if (aMillisDelay > SERVO_REFRESH_INTERVAL_MILLIS) {
2666  aMillisDelay -= SERVO_REFRESH_INTERVAL_MILLIS;
2667  delay(SERVO_REFRESH_INTERVAL_MILLIS); // 20 ms
2668  if (updateAllServos() && aTerminateDelayIfAllServosStopped) {
2669  // terminate delay here and return
2670  return true;
2671  }
2672  } else {
2673  delay(aMillisDelay);
2674  return updateAllServos();
2675  }
2676  }
2677 }
2678 
2685 }
2686 
2691 void synchronizeAllServosAndStartInterrupt(bool aStartUpdateByInterrupt, bool aSynchronizeToMinimumDuration) {
2692  /*
2693  * Find maximum duration and one start time
2694  */
2695  uint_fast16_t tMillisForCompleteMove = 0;
2696  if (aSynchronizeToMinimumDuration) {
2697  tMillisForCompleteMove = __UINT16_MAX__;
2698  }
2699  uint32_t tMillisAtStartMove = 0;
2700 
2701  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2702  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr && ServoEasing::ServoEasingArray[tServoIndex]->mServoMoves) {
2703  // Here we process only servos which really moves
2704  if (aSynchronizeToMinimumDuration) {
2705  if (tMillisForCompleteMove > ServoEasing::ServoEasingArray[tServoIndex]->mMillisForCompleteMove) {
2706  tMillisForCompleteMove = ServoEasing::ServoEasingArray[tServoIndex]->mMillisForCompleteMove;
2707  }
2708  } else {
2709  if (tMillisForCompleteMove < ServoEasing::ServoEasingArray[tServoIndex]->mMillisForCompleteMove) {
2710  tMillisForCompleteMove = ServoEasing::ServoEasingArray[tServoIndex]->mMillisForCompleteMove;
2711  }
2712  }
2713  // Any value is OK, but it must be of an active servo
2714  tMillisAtStartMove = ServoEasing::ServoEasingArray[tServoIndex]->mMillisAtStartMove;
2715  }
2716  }
2717 
2718 #if defined(LOCAL_TRACE)
2719  Serial.print(ServoEasing::sServoArrayMaxIndex + 1);
2720  Serial.print(F(" servos, MillisAtStartMove="));
2721  Serial.print(tMillisAtStartMove);
2722  Serial.print(F(", MillisForCompleteMove="));
2723  Serial.println(tMillisForCompleteMove);
2724  Serial.flush();
2725 #endif
2726 
2727  /*
2728  * Set maximum duration and start time to all servos
2729  * Synchronize start time to avoid race conditions at the end of movement
2730  */
2731  for (uint_fast8_t tServoIndex = 0; tServoIndex <= ServoEasing::sServoArrayMaxIndex; ++tServoIndex) {
2732  if (ServoEasing::ServoEasingArray[tServoIndex] != nullptr && ServoEasing::ServoEasingArray[tServoIndex]->mServoMoves) {
2733  ServoEasing::ServoEasingArray[tServoIndex]->mMillisAtStartMove = tMillisAtStartMove; // let them all start at the same time
2734  ServoEasing::ServoEasingArray[tServoIndex]->mMillisForCompleteMove = tMillisForCompleteMove;
2735  }
2736  }
2737 
2738  if (aStartUpdateByInterrupt) {
2740  }
2741 }
2742 
2743 #if !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
2744 /*********************************************************
2745  * Included easing functions
2746  * Input is from 0.0 to 1.0 with 0.0 -> 0 % and 1.0 -> 100% completion of time between the two endpoints
2747  * Output is from 0.0 to 1.0 with: 0.0 -> 0 % and 1.0 -> 100% completion of movement (e.g. 1.1 is 10% overshot)
2748  ********************************************************/
2749 //float (*sEaseFunctionArray[])(
2750 // float aFactorOfTimeCompletion) = {&QuadraticEaseIn, &CubicEaseIn, &QuarticEaseIn, &SineEaseIn, &CircularEaseIn, &BackEaseIn, &ElasticEaseIn,
2751 // &EaseOutBounce};
2755 float ServoEasing::QuadraticEaseIn(float aFactorOfTimeCompletion) {
2756  return (aFactorOfTimeCompletion * aFactorOfTimeCompletion);
2757 }
2758 
2759 float ServoEasing::CubicEaseIn(float aFactorOfTimeCompletion) {
2760  return (aFactorOfTimeCompletion * QuadraticEaseIn(aFactorOfTimeCompletion));
2761 }
2762 
2763 float ServoEasing::QuarticEaseIn(float aFactorOfTimeCompletion) {
2764  return QuadraticEaseIn(QuadraticEaseIn(aFactorOfTimeCompletion));
2765 }
2766 
2771 float ServoEasing::SineEaseIn(float aFactorOfTimeCompletion) {
2772  return sin((aFactorOfTimeCompletion - 1) * M_PI_2) + 1;
2773 }
2774 
2780 float ServoEasing::CircularEaseIn(float aFactorOfTimeCompletion) {
2781  return 1 - sqrt(1 - (aFactorOfTimeCompletion * aFactorOfTimeCompletion));
2782 }
2783 
2788 float ServoEasing::BackEaseIn(float aFactorOfTimeCompletion) {
2789  return (aFactorOfTimeCompletion * aFactorOfTimeCompletion * aFactorOfTimeCompletion)
2790  - (aFactorOfTimeCompletion * sin(aFactorOfTimeCompletion * M_PI));
2791 }
2792 
2797 float ServoEasing::ElasticEaseIn(float aFactorOfTimeCompletion) {
2798  return sin(13 * M_PI_2 * aFactorOfTimeCompletion) * pow(2, 10 * (aFactorOfTimeCompletion - 1));
2799 }
2800 
2801 #define PART_OF_LINEAR_MOVEMENT 0.8
2802 #define PART_OF_BOUNCE_MOVEMENT (1.0 - PART_OF_LINEAR_MOVEMENT)
2803 #define PART_OF_BOUNCE_MOVEMENT_HALF ((1.0 - PART_OF_LINEAR_MOVEMENT) / 2) // 0.1
2805 #define OVERSHOOT_AMOUNT_MILLIS 50 // around 5 degree
2806 #define OVERSHOOT_AMOUNT_UNITS 10 // around 5 degree
2815 float ServoEasing::LinearWithQuadraticBounce(float aFactorOfTimeCompletion) {
2817  || ((mEasingType & CALL_STYLE_OUT) == 0 && mDeltaMicrosecondsOrUnits >= 0)) {
2818  // Use linear moving for this direction/type combination.
2819  return aFactorOfTimeCompletion;
2820  } else {
2821  if (mEasingType & CALL_STYLE_OUT) {
2822  aFactorOfTimeCompletion = 1 - aFactorOfTimeCompletion; // reverse the reverse calling :-) so we have from 0.0 to 1.0
2823  }
2824 
2825  /*
2826  * We are approaching from the direction, which requires a bounce.
2827  * Use scaled linear moving the first 80 % of the movement, and add a quadratic bounce for the remaining 20%.
2828  */
2829  if (aFactorOfTimeCompletion < PART_OF_LINEAR_MOVEMENT) {
2830  // The linear part, return scaled up float aFactorOfTimeCompletion
2831  aFactorOfTimeCompletion = aFactorOfTimeCompletion * (1.0 / PART_OF_LINEAR_MOVEMENT);
2832  if (mEasingType & CALL_STYLE_OUT) {
2833  return 1 - aFactorOfTimeCompletion; // must return reverse factor
2834  }
2835  return aFactorOfTimeCompletion; // for IN function, return plain factor
2836 
2837  } else {
2838  /*
2839  * The bounce for the IN function (aFactorOfTimeCompletion from 0.8 to 1.0)
2840  */
2841  float tRemainingFactor;
2842  if (aFactorOfTimeCompletion < (1.0 - PART_OF_BOUNCE_MOVEMENT_HALF)) {
2843  // Between 80 % and 90 % here. Starting part of the overshoot bounce
2844  tRemainingFactor = aFactorOfTimeCompletion - PART_OF_LINEAR_MOVEMENT; // tRemainingFactor - 0.8 -> 0.0 to 0.1
2845  tRemainingFactor = tRemainingFactor * (1 / PART_OF_BOUNCE_MOVEMENT_HALF); // tRemainingFactor is 0.0 to 1.0
2846  tRemainingFactor = 1.0 - tRemainingFactor; // tRemainingFactor is 1.0 to 0.0 -> quadratic out
2847  } else {
2848  // Between 90 % and 100 % here. Returning part of the overshoot bounce
2849  tRemainingFactor = aFactorOfTimeCompletion - (1.0 - PART_OF_BOUNCE_MOVEMENT_HALF); // tRemainingFactor - 0.9 -> 0.0 to 0.1
2850  tRemainingFactor = tRemainingFactor * (1 / PART_OF_BOUNCE_MOVEMENT_HALF); // tRemainingFactor is 0.0 to 1.0 -> quadratic in
2851  }
2852 
2853  uint_fast8_t tBumpMicrosecondsOrUnits = OVERSHOOT_AMOUNT_MILLIS;
2854 #if defined(USE_PCA9685_SERVO_EXPANDER)
2855 # if defined(USE_SERVO_LIB)
2856  if (mServoIsConnectedToExpander) {
2857  tBumpMicrosecondsOrUnits = OVERSHOOT_AMOUNT_UNITS;
2858  } else {
2859  tBumpMicrosecondsOrUnits = OVERSHOOT_AMOUNT_MILLIS;
2860  }
2861 # else
2862  tBumpMicrosecondsOrUnits = OVERSHOOT_AMOUNT_UNITS;
2863 # endif
2864 #else
2865  tBumpMicrosecondsOrUnits = OVERSHOOT_AMOUNT_MILLIS;
2866 #endif
2867  // return direct microseconds or units values for constant bump
2868  if (mEasingType & CALL_STYLE_OUT) {
2869  /*
2870  * Positive bounce for movings from below
2871  * must compensate for processing at update by: tFactorOfMovementCompletion = 1.0 - (callEasingFunction(1.0 - tFactorOfTimeCompletion));
2872  */
2873  return -(mEndMicrosecondsOrUnits + tBumpMicrosecondsOrUnits - 1
2874  - (tBumpMicrosecondsOrUnits * tRemainingFactor * tRemainingFactor));
2875  } else {
2876  /*
2877  * Negative bounce for movings from above
2878  */
2879  return mEndMicrosecondsOrUnits + (tBumpMicrosecondsOrUnits * tRemainingFactor * tRemainingFactor)
2880  - tBumpMicrosecondsOrUnits;
2881  }
2882  }
2883  }
2884 }
2885 
2891 float ServoEasing::EaseOutBounce(float aFactorOfTimeCompletion) {
2892  float tFactorOfMovementCompletion;
2893  if (aFactorOfTimeCompletion < 4 / 11.0) {
2894  tFactorOfMovementCompletion = (121 * aFactorOfTimeCompletion * aFactorOfTimeCompletion) / 16.0;
2895  } else if (aFactorOfTimeCompletion < 8 / 11.0) {
2896  tFactorOfMovementCompletion = (363 / 40.0 * aFactorOfTimeCompletion * aFactorOfTimeCompletion)
2897  - (99 / 10.0 * aFactorOfTimeCompletion) + 17 / 5.0;
2898  } else if (aFactorOfTimeCompletion < 9 / 10.0) {
2899  tFactorOfMovementCompletion = (4356 / 361.0 * aFactorOfTimeCompletion * aFactorOfTimeCompletion)
2900  - (35442 / 1805.0 * aFactorOfTimeCompletion) + 16061 / 1805.0;
2901  } else {
2902  tFactorOfMovementCompletion = (54 / 5.0 * aFactorOfTimeCompletion * aFactorOfTimeCompletion)
2903  - (513 / 25.0 * aFactorOfTimeCompletion) + 268 / 25.0;
2904  }
2905  return tFactorOfMovementCompletion;
2906 }
2907 #endif // !defined(PROVIDE_ONLY_LINEAR_MOVEMENT)
2908 
2909 /************************************
2910  * Convenience I2C check function
2911  * One version as class methods and one version as static function
2912  ***********************************/
2913 #if defined(USE_PCA9685_SERVO_EXPANDER)
2914 
2920 #if defined(__AVR__)
2921 bool ServoEasing::InitializeAndCheckI2CConnection(Print *aSerial) // Print instead of Stream saves 95 bytes flash
2922 #else
2923 bool ServoEasing::InitializeAndCheckI2CConnection(Stream *aSerial) // Print has no flush()
2924 #endif
2925 {
2926  return initializeAndCheckI2CConnection(aSerial);
2927 }
2928 #if defined(__AVR__)
2929 bool ServoEasing::initializeAndCheckI2CConnection(Print *aSerial) // Print instead of Stream saves 95 bytes flash
2930 #else
2931 bool ServoEasing::initializeAndCheckI2CConnection(Stream *aSerial) // Print has no flush()
2932 #endif
2933  {
2934 #if !defined(USE_SOFT_I2C_MASTER)
2935  // Initialize wire before checkI2CConnection()
2936  I2CInit();
2937 #endif
2938  return checkI2CConnection(mPCA9685I2CAddress, aSerial);
2939 }
2940 
2941 #if defined(__AVR__)
2942 bool checkI2CConnection(uint8_t aI2CAddress, Print *aSerial) // Print instead of Stream saves 95 bytes flash
2943 #else
2944 bool checkI2CConnection(uint8_t aI2CAddress, Stream *aSerial) // Print has no flush(), so we must take Stream
2945 #endif
2946  {
2947 
2948  bool tRetValue = false;
2949  aSerial->print(F("Try to communicate with " STR(I2C_CLOCK_FREQUENCY) " Hz with I2C device at address=0x"));
2950  aSerial->println(aI2CAddress, HEX);
2951  aSerial->flush();
2952 
2953  // Initialize wire
2954 #if defined(USE_SOFT_I2C_MASTER)
2955  if(i2c_init()){
2956  if(!i2c_start(aI2CAddress << 1)){
2957  aSerial->println(F("No acknowledge received from the slave"));
2958  aSerial->print(F("Communication with I2C was successful, but found no"));
2959  tRetValue = true;
2960  } else {
2961  aSerial->print(F("Found"));
2962  }
2963  i2c_stop();
2964  aSerial->print(F(" I2C device attached at address: 0x"));
2965  aSerial->println(aI2CAddress, HEX);
2966  } else {
2967  aSerial->println(F("I2C init failed"));
2968  }
2969 #else // defined(USE_SOFT_I2C_MASTER)
2970 
2971 # if defined (ARDUINO_ARCH_AVR) // Other platforms do not have this new function
2972  do {
2973  Wire.beginTransmission(aI2CAddress);
2974  if (Wire.getWireTimeoutFlag()) {
2975  aSerial->println(F("Timeout accessing I2C bus. Wait for bus becoming available"));
2976  Wire.clearWireTimeoutFlag();
2977  delay(100);
2978  } else {
2979  break;
2980  }
2981  } while (true);
2982 # else
2983  Wire.beginTransmission(aI2CAddress);
2984 # endif
2985 
2986  uint8_t tWireReturnCode = Wire.endTransmission(true);
2987  if (tWireReturnCode == 0) {
2988  aSerial->print(F("Found"));
2989  } else {
2990  aSerial->print(F("Error code="));
2991  aSerial->print(tWireReturnCode);
2992  aSerial->print(F(". Communication with I2C was successful, but found no"));
2993  tRetValue = true;
2994  }
2995  aSerial->print(F(" I2C device attached at address: 0x"));
2996  aSerial->println(aI2CAddress, HEX);
2997 #endif // defined(USE_SOFT_I2C_MASTER)
2998 
2999  if (tRetValue) {
3000  aSerial->println(F("PCA9685 expander not connected. Check power supply, try to reduce I2C clock of " STR(I2C_CLOCK_FREQUENCY) " Hz (I2C_CLOCK_FREQUENCY in ServoEasing.h) or pull-up resistor values."));
3001  }
3002  return tRetValue;
3003 }
3004 # endif // defined(USE_PCA9685_SERVO_EXPANDER)
3005 
3006 #if defined(LOCAL_DEBUG)
3007 #undef LOCAL_DEBUG
3008 #endif
3009 #if defined(LOCAL_TRACE)
3010 #undef LOCAL_TRACE
3011 #endif
3012 #endif // _SERVO_EASING_HPP
ServoEasing::getDeltaMicrosecondsOrUnits
int getDeltaMicrosecondsOrUnits()
Definition: ServoEasing.hpp:1822
setEaseToForAllServos
bool setEaseToForAllServos()
Sets target position using content of ServoEasingNextPositionArray.
Definition: ServoEasing.hpp:2535
PROGMEM
const char easeTypeLinear[] PROGMEM
Definition: ServoEasing.hpp:164
setEasingTypeForMultipleServos
void setEasingTypeForMultipleServos(uint_fast8_t aNumberOfServos, uint_fast8_t aEasingType)
Sets easing type aEasingType for the first aNumberOfServos in ServoEasingArray[].
Definition: ServoEasing.hpp:2393
ServoEasing::_setTrimMicrosecondsOrUnits
void _setTrimMicrosecondsOrUnits(int aTrimMicrosecondsOrUnits, bool aDoWrite=false)
Definition: ServoEasing.hpp:807
ServoEasing::MicrosecondsOrUnitsToDegree
int MicrosecondsOrUnitsToDegree(int aMicrosecondsOrUnits)
Used to convert e.g.
Definition: ServoEasing.hpp:1029
ServoEasing::areInterruptsActive
static bool areInterruptsActive()
The recommended test if at least one servo is moving yet.
Definition: ServoEasing.hpp:1774
updateAllServos
bool updateAllServos()
Definition: ServoEasing.hpp:2630
ServoEasing::getSpeed
uint_fast16_t getSpeed()
Definition: ServoEasing.hpp:775
ServoEasing::mSpeed
uint_fast16_t mSpeed
max speed is 450 degree/sec for SG90 and 540 degree/second for MG90 servos -> see speedTest....
Definition: ServoEasing.h:653
ServoEasing::mServoMoves
volatile bool mServoMoves
Definition: ServoEasing.h:663
ServoEasing::_writeMicrosecondsOrUnits
void _writeMicrosecondsOrUnits(int aTargetMicrosecondsOrUnits)
Internal function Before sending the value to the underlying Servo library, trim and reverse is appli...
Definition: ServoEasing.hpp:902
ServoEasing::update
bool update()
Definition: ServoEasing.hpp:1558
synchronizeAndEaseToArrayPositions
void synchronizeAndEaseToArrayPositions()
Definition: ServoEasing.hpp:2426
ServoEasing::mLastTargetMicrosecondsOrUnits
volatile int mLastTargetMicrosecondsOrUnits
Internally only microseconds (or units (= 4.88 us) if using PCA9685 expander) and not degree are used...
Definition: ServoEasing.h:645
ServoEasing::attach
uint8_t attach(int aPin)
Specify the microseconds values for 0 and 180 degree for the servo.
Definition: ServoEasing.hpp:473
ServoEasing
Definition: ServoEasing.h:458
ServoEasing::readMicroseconds
int readMicroseconds()
Definition: ServoEasing.hpp:1807
ServoEasing::setReverseOperation
void setReverseOperation(bool aOperateServoReverse)
Definition: ServoEasing.hpp:771
ServoEasing::getEasingType
uint_fast8_t getEasingType()
Definition: ServoEasing.hpp:840
CALL_STYLE_DIRECT
#define CALL_STYLE_DIRECT
Definition: ServoEasing.h:325
ServoEasing::TargetPositionReachedHandler
void(* TargetPositionReachedHandler)(ServoEasing *)
Is called any time when target servo position is reached.
Definition: ServoEasing.h:705
ServoEasing::mStartMicrosecondsOrUnits
int mStartMicrosecondsOrUnits
Only used with millisAtStartMove to compute currentMicrosecondsOrUnits in update()
Definition: ServoEasing.h:646
ServoEasing::getMillisForCompleteMove
int getMillisForCompleteMove()
Definition: ServoEasing.hpp:1826
PART_OF_LINEAR_MOVEMENT
#define PART_OF_LINEAR_MOVEMENT
Definition: ServoEasing.hpp:2801
ServoEasing::setTargetPositionReachedHandler
void setTargetPositionReachedHandler(void(*aTargetPositionReachedHandler)(ServoEasing *))
Definition: ServoEasing.hpp:1516
ServoEasing::mServo0DegreeMicrosecondsOrUnits
int mServo0DegreeMicrosecondsOrUnits
Values contain always microseconds except for servos connected to a PCA9685 expander,...
Definition: ServoEasing.h:702
CALL_STYLE_BOUNCING_OUT_IN
#define CALL_STYLE_BOUNCING_OUT_IN
Definition: ServoEasing.h:329
ServoEasing::mTrimMicrosecondsOrUnits
int mTrimMicrosecondsOrUnits
This value is always added by the function _writeMicrosecondsOrUnits() to the requested degree/units/...
Definition: ServoEasing.h:696
CALL_STYLE_MASK
#define CALL_STYLE_MASK
Definition: ServoEasing.h:331
CALL_STYLE_IN
#define CALL_STYLE_IN
Definition: ServoEasing.h:326
printArrayPositions
void printArrayPositions(Print *aSerial)
Prints content of ServoNextPositionArray for debugging purposes.
Definition: ServoEasing.hpp:2440
OVERSHOOT_AMOUNT_UNITS
#define OVERSHOOT_AMOUNT_UNITS
Definition: ServoEasing.hpp:2806
ServoEasing::mServoPin
uint8_t mServoPin
pin number / port number of PCA9685 [0-15] or NO_SERVO_ATTACHED_PIN_NUMBER - at least required for Li...
Definition: ServoEasing.h:675
writeAllServos
void writeAllServos(int aDegreeOrMicrosecond)
Definition: ServoEasing.hpp:2467
ServoEasing::setEaseTo
bool setEaseTo(int aTargetDegreeOrMicrosecond)
Definition: ServoEasing.hpp:1209
EASE_CUBIC_IN
#define EASE_CUBIC_IN
Definition: ServoEasing.h:344
EASE_FUNCTION_DEGREE_THRESHOLD
#define EASE_FUNCTION_DEGREE_THRESHOLD
Definition: ServoEasing.h:318
ServoEasing::getEndMicrosecondsOrUnits
int getEndMicrosecondsOrUnits()
Definition: ServoEasing.hpp:1811
PCA9685_FIRST_PWM_REGISTER
#define PCA9685_FIRST_PWM_REGISTER
Definition: ServoEasing.h:437
ServoEasing::resumeWithInterrupts
void resumeWithInterrupts()
Definition: ServoEasing.hpp:1501
DO_NOT_START_UPDATE_BY_INTERRUPT
#define DO_NOT_START_UPDATE_BY_INTERRUPT
Definition: ServoEasing.h:448
ServoEasing::stop
void stop()
This stops the servo at any position.
Definition: ServoEasing.hpp:1484
ServoEasing::attachWithTrim
uint8_t attachWithTrim(int aPin, int aTrimDegreeOrMicrosecond, int aInitialDegreeOrMicrosecond)
Combination of attach with initial setTrim() and write().
Definition: ServoEasing.hpp:492
ServoEasing::noMovement
bool noMovement(uint_fast16_t aMillisToWait)
stay at the position for aMillisToWait Used as delay for callback
Definition: ServoEasing.hpp:1357
checkI2CConnection
bool checkI2CConnection(uint8_t aI2CAddress, Stream *aSerial)
ServoEasing::isMoving
bool isMoving()
Test if servo is moving yet.
Definition: ServoEasing.hpp:1761
DEFAULT_PCA9685_UNITS_FOR_180_DEGREE
#define DEFAULT_PCA9685_UNITS_FOR_180_DEGREE
Definition: ServoEasing.h:257
setEaseToForAllServosSynchronizeAndWaitForAllServosToStop
void setEaseToForAllServosSynchronizeAndWaitForAllServosToStop()
Synchronize and blocking wait until all servos are stopped Take the longer duration in order to move ...
Definition: ServoEasing.hpp:2416
EASE_FUNCTION_DEGREE_INDICATOR_OFFSET
#define EASE_FUNCTION_DEGREE_INDICATOR_OFFSET
Definition: ServoEasing.h:317
ServoEasing::setUserDataPointer
void setUserDataPointer(void *aUserDataPointer)
Definition: ServoEasing.hpp:850
EASE_BOUNCE_OUT
#define EASE_BOUNCE_OUT
Definition: ServoEasing.h:398
MAXIMUM_PULSE_WIDTH
#define MAXIMUM_PULSE_WIDTH
Definition: ServoEasing.h:242
pauseAllServos
void pauseAllServos()
Definition: ServoEasing.hpp:2599
ServoEasing::pause
void pause()
Definition: ServoEasing.hpp:1494
ServoEasing::mServoIsPaused
bool mServoIsPaused
Definition: ServoEasing.h:682
EASE_LINEAR
#define EASE_LINEAR
Definition: ServoEasing.h:334
stopAllServos
void stopAllServos()
Definition: ServoEasing.hpp:2588
ServoEasing::printExtra
void printExtra(Print *aSerial)
Definition: ServoEasing.hpp:1980
ServoEasing::BackEaseIn
static float BackEaseIn(float aPercentageOfCompletion)
see: https://easings.net/#easeInOutBack and https://github.com/warrenm/AHEasing/blob/master/AHEasing/...
Definition: ServoEasing.hpp:2788
ServoEasing::mEndMicrosecondsOrUnits
int mEndMicrosecondsOrUnits
Only used once as last value if movement was finished to provide exact end position.
Definition: ServoEasing.h:647
synchronizeAllServosStartAndWaitForAllServosToStop
void synchronizeAllServosStartAndWaitForAllServosToStop()
Synchronize and blocking wait until all servos are stopped.
Definition: ServoEasing.hpp:2682
ServoEasing::DegreeToMicrosecondsOrUnitsWithTrimAndReverse
int DegreeToMicrosecondsOrUnitsWithTrimAndReverse(int aDegree)
Mainly for testing, since trim and reverse are applied at each write.
Definition: ServoEasing.hpp:1136
ServoEasing::applyTrimAndReverseToTargetMicrosecondsOrUnits
int applyTrimAndReverseToTargetMicrosecondsOrUnits(int aTargetMicrosecondsOrUnits)
Definition: ServoEasing.hpp:1863
clipDegreeSpecial
int clipDegreeSpecial(uint_fast8_t aDegreeToClip)
Clips the unsigned degree value and handles unsigned underflow.
Definition: ServoEasing.hpp:1991
PCA9685_MODE_1_AUTOINCREMENT
#define PCA9685_MODE_1_AUTOINCREMENT
Definition: ServoEasing.h:434
PCA9685_PRESCALER_FOR_20_MS
#define PCA9685_PRESCALER_FOR_20_MS
Definition: ServoEasing.h:444
EASE_USER_DIRECT
#define EASE_USER_DIRECT
Definition: ServoEasing.h:358
CALL_STYLE_IN_OUT
#define CALL_STYLE_IN_OUT
Definition: ServoEasing.h:328
ServoEasing::LinearWithQuadraticBounce
float LinearWithQuadraticBounce(float aPercentageOfCompletion)
PRECISION (LinearWithQuadraticBounce) is like linear, but adds a 5 degree bounce in the last 20 % of ...
Definition: ServoEasing.hpp:2815
isOneServoMoving
bool isOneServoMoving()
Definition: ServoEasing.hpp:2579
CALL_STYLE_OUT
#define CALL_STYLE_OUT
Definition: ServoEasing.h:327
ServoEasing::setTrim
void setTrim(int aTrimDegreeOrMicrosecond, bool aDoWrite=false)
Definition: ServoEasing.hpp:789
ServoEasing::printDynamic
void printDynamic(Print *aSerial, bool doExtendedOutput=true)
Prints values which may change from move to move.
Definition: ServoEasing.hpp:1877
DEFAULT_PULSE_WIDTH
#define DEFAULT_PULSE_WIDTH
Definition: ServoEasing.h:182
ServoEasing::mEasingType
uint8_t mEasingType
Definition: ServoEasing.h:656
ServoEasing::MicrosecondsOrUnitsToMicroseconds
int MicrosecondsOrUnitsToMicroseconds(int aMicrosecondsOrUnits)
Definition: ServoEasing.hpp:1066
PCA9685_MODE1_EXTCLK
#define PCA9685_MODE1_EXTCLK
Definition: ServoEasing.h:436
ServoEasing::mMillisForCompleteMove
uint_fast16_t mMillisForCompleteMove
Definition: ServoEasing.h:680
ServoEasing::EaseOutBounce
static float EaseOutBounce(float aPercentageOfCompletion)
!!! ATTENTION !!! we have only the out function implemented see: https://easings.net/de#easeOutBounce...
Definition: ServoEasing.hpp:2891
EASE_BACK_IN
#define EASE_BACK_IN
Definition: ServoEasing.h:382
delayAndUpdateAndWaitForAllServosToStop
bool delayAndUpdateAndWaitForAllServosToStop(unsigned long aMillisDelay, bool aTerminateDelayIfAllServosStopped)
Definition: ServoEasing.hpp:2662
ServoEasing::resumeWithoutInterrupts
void resumeWithoutInterrupts()
Definition: ServoEasing.hpp:1509
ServoEasing::print
void print(Print *aSerial, bool doExtendedOutput=true)
Do a printDynamic() and a printStatic()
Definition: ServoEasing.hpp:1835
ServoEasing::mMillisAtStartMove
uint32_t mMillisAtStartMove
Definition: ServoEasing.h:679
ServoEasing::easeToD
void easeToD(int aTargetDegreeOrMicrosecond, uint_fast16_t aMillisForMove)
Definition: ServoEasing.hpp:1183
ServoEasing::mUserEaseInFunction
float(* mUserEaseInFunction)(float aPercentageOfCompletion, void *aUserDataPointer)
Definition: ServoEasing.h:659
ServoEasing::getCurrentAngle
int getCurrentAngle()
Definition: ServoEasing.hpp:1795
ServoEasing::MicrosecondsToDegree
int MicrosecondsToDegree(int aMicroseconds)
Only used in startEaseTo to compute target degree For PCA9685, we have stored units in mServo0DegreeM...
Definition: ServoEasing.hpp:1009
DEFAULT_MICROSECONDS_FOR_0_DEGREE
#define DEFAULT_MICROSECONDS_FOR_0_DEGREE
Definition: ServoEasing.h:246
ServoEasing::printStatic
void printStatic(Print *aSerial)
Prints values which normally does NOT change from move to move.
Definition: ServoEasing.hpp:1936
synchronizeAllServosAndStartInterrupt
void synchronizeAllServosAndStartInterrupt(bool aStartUpdateByInterrupt, bool aSynchronizeToMinimumDuration)
Take the longest duration in order to move all servos synchronously.
Definition: ServoEasing.hpp:2691
MINIMUM_PULSE_WIDTH
#define MINIMUM_PULSE_WIDTH
Definition: ServoEasing.h:239
EASE_QUADRATIC_IN
#define EASE_QUADRATIC_IN
Definition: ServoEasing.h:337
ServoEasing::callEasingFunction
float callEasingFunction(float aPercentageOfCompletion)
Definition: ServoEasing.hpp:1700
PCA9685_SOFTWARE_RESET
#define PCA9685_SOFTWARE_RESET
Definition: ServoEasing.h:429
resumeWithoutInterruptsAllServos
void resumeWithoutInterruptsAllServos()
Definition: ServoEasing.hpp:2619
ServoEasing::startEaseToD
bool startEaseToD(int aTargetDegreeOrMicrosecond, uint_fast16_t aMillisForMove, bool aStartUpdateByInterrupt=START_UPDATE_BY_INTERRUPT)
Sets up all the values required for a smooth move to new value Lower level function with time instead...
Definition: ServoEasing.hpp:1370
ServoEasing::CircularEaseIn
static float CircularEaseIn(float aPercentageOfCompletion)
It is very fast in the middle! see: https://easings.net/#easeInOutCirc and https://github....
Definition: ServoEasing.hpp:2780
handleServoTimerInterrupt
void handleServoTimerInterrupt()
Update all servos from list and check if all servos have stopped.
Definition: ServoEasing.hpp:2012
PCA9685_MODE1_REGISTER
#define PCA9685_MODE1_REGISTER
Definition: ServoEasing.h:432
ServoEasing::detach
void detach()
No servo signal is generated for a detached servo / the output is constant LOW.
Definition: ServoEasing.hpp:730
ServoEasing::mMillisAtStopMove
uint32_t mMillisAtStopMove
Definition: ServoEasing.h:683
SERVO_REFRESH_FREQUENCY
#define SERVO_REFRESH_FREQUENCY
Definition: ServoEasing.h:197
EASE_TYPE_MASK
#define EASE_TYPE_MASK
Definition: ServoEasing.h:332
PCA9685_GENERAL_CALL_ADDRESS
#define PCA9685_GENERAL_CALL_ADDRESS
Definition: ServoEasing.h:428
ServoEasing::startEaseTo
bool startEaseTo(int aTargetDegreeOrMicrosecond)
Definition: ServoEasing.hpp:1235
EASE_ELASTIC_IN
#define EASE_ELASTIC_IN
Definition: ServoEasing.h:389
SERVO_REFRESH_INTERVAL_MICROS
#define SERVO_REFRESH_INTERVAL_MICROS
Definition: ServoEasing.h:191
THRESHOLD_VALUE_FOR_INTERPRETING_VALUE_AS_MICROSECONDS
#define THRESHOLD_VALUE_FOR_INTERPRETING_VALUE_AS_MICROSECONDS
Definition: ServoEasing.h:223
setSpeedForAllServos
void setSpeedForAllServos(uint_fast16_t aDegreesPerSecond)
Definition: ServoEasing.hpp:2475
STR
#define STR(x)
Definition: ServoEasing.h:796
LightweightServo.hpp
ServoEasing::getEndMicrosecondsOrUnitsWithTrim
int getEndMicrosecondsOrUnitsWithTrim()
Not used internally.
Definition: ServoEasing.hpp:1818
ServoEasing::ServoEasing
ServoEasing()
Definition: ServoEasing.hpp:426
ServoEasing::reattach
uint8_t reattach()
Definition: ServoEasing.hpp:547
Servo::Servo
Servo()
ServoEasing::ServoEasingNextPositionArray
static float ServoEasingNextPositionArray[MAX_EASING_SERVOS]
Used exclusively for *ForAllServos() functions.
Definition: ServoEasing.h:722
ServoEasing::getCurrentMicroseconds
int getCurrentMicroseconds()
Definition: ServoEasing.hpp:1803
SERVO_REFRESH_INTERVAL_MILLIS
#define SERVO_REFRESH_INTERVAL_MILLIS
Definition: ServoEasing.h:196
ServoEasing::sInterruptsAreActive
static volatile bool sInterruptsAreActive
It is required for ESP32, where the timer interrupt routine does not block the loop.
Definition: ServoEasing.h:713
EASE_QUARTIC_IN
#define EASE_QUARTIC_IN
Definition: ServoEasing.h:351
ServoEasing::mServo180DegreeMicrosecondsOrUnits
int mServo180DegreeMicrosecondsOrUnits
Definition: ServoEasing.h:703
PART_OF_BOUNCE_MOVEMENT_HALF
#define PART_OF_BOUNCE_MOVEMENT_HALF
Definition: ServoEasing.hpp:2803
START_EASE_TO_SPEED
#define START_EASE_TO_SPEED
Definition: ServoEasing.h:50
Servo::writeMicroseconds
void writeMicroseconds(int value)
ServoEasing::printEasingType
static void printEasingType(Print *aSerial, uint_fast8_t aEasingType)
Definition: ServoEasing.hpp:1844
Servo::detach
void detach()
DEFAULT_PCA9685_UNITS_FOR_90_DEGREE
#define DEFAULT_PCA9685_UNITS_FOR_90_DEGREE
Definition: ServoEasing.h:255
ServoEasing::ServoEasingArray
static ServoEasing * ServoEasingArray[MAX_EASING_SERVOS]
Definition: ServoEasing.h:721
EASE_DUMMY_MOVE
#define EASE_DUMMY_MOVE
Definition: ServoEasing.h:365
MAX_EASING_SERVOS
#define MAX_EASING_SERVOS
Definition: ServoEasing.h:177
ServoEasing::DegreeOrMicrosecondToMicrosecondsOrUnits
int DegreeOrMicrosecondToMicrosecondsOrUnits(int aDegreeOrMicrosecond)
We have around 10 us per degree Used to convert (external) provided degree values to internal microse...
Definition: ServoEasing.hpp:1080
INVALID_SERVO
#define INVALID_SERVO
Definition: ServoEasing.h:194
ServoEasing::QuadraticEaseIn
static float QuadraticEaseIn(float aPercentageOfCompletion)
The simplest non linear easing function.
Definition: ServoEasing.hpp:2755
setEasingTypeForAllServos
void setEasingTypeForAllServos(uint_fast8_t aEasingType)
60 us for single servo + 160 us per servo if using I2C e.g.for PCA9685 expander at 400 kHz or + 100 a...
Definition: ServoEasing.hpp:2386
ServoEasing::UserDataPointer
void * UserDataPointer
Definition: ServoEasing.h:658
updateAndWaitForAllServosToStop
void updateAndWaitForAllServosToStop()
Blocking wait until all servos are stopped.
Definition: ServoEasing.hpp:2650
ServoEasing::registerUserEaseInFunction
void registerUserEaseInFunction(float(*aUserEaseInFunction)(float aPercentageOfCompletion, void *aUserDataPointer), void *aUserDataPointer=nullptr)
Definition: ServoEasing.hpp:845
START_UPDATE_BY_INTERRUPT
#define START_UPDATE_BY_INTERRUPT
Definition: ServoEasing.h:447
ServoEasing::SineEaseIn
static float SineEaseIn(float aPercentageOfCompletion)
Take half of negative cosines of first quadrant Is behaves almost like QUADRATIC.
Definition: ServoEasing.hpp:2771
setEaseToForAllServosSynchronizeAndStartInterrupt
void setEaseToForAllServosSynchronizeAndStartInterrupt()
Definition: ServoEasing.hpp:2402
ServoEasing::mOperateServoReverse
bool mOperateServoReverse
Reverse means, that values for 180 and 0 degrees are swapped by: aValue = mServo180DegreeMicroseconds...
Definition: ServoEasing.h:691
EASE_CIRCULAR_IN
#define EASE_CIRCULAR_IN
Definition: ServoEasing.h:375
PCA9685_MODE_1_SLEEP
#define PCA9685_MODE_1_SLEEP
Definition: ServoEasing.h:435
ServoEasing::read
int read()
Definition: ServoEasing.hpp:1799
disableServoEasingInterrupt
void disableServoEasingInterrupt()
Definition: ServoEasing.hpp:2257
ServoEasing::sServoArrayMaxIndex
static uint_fast8_t sServoArrayMaxIndex
Two arrays of all servos to enable synchronized movings Servos are inserted in the order,...
Definition: ServoEasing.h:720
ServoEasing.h
DEFAULT_MICROSECONDS_FOR_180_DEGREE
#define DEFAULT_MICROSECONDS_FOR_180_DEGREE
Definition: ServoEasing.h:250
OVERSHOOT_AMOUNT_MILLIS
#define OVERSHOOT_AMOUNT_MILLIS
Definition: ServoEasing.hpp:2805
ServoEasing::mDeltaMicrosecondsOrUnits
int mDeltaMicrosecondsOrUnits
end - start
Definition: ServoEasing.h:648
ServoEasing::setEaseToD
bool setEaseToD(int aTargetDegreeOrMicrosecond, uint_fast16_t aDegreesPerSecond)
Definition: ServoEasing.hpp:1345
ServoEasing::mServoIndex
uint8_t mServoIndex
Index in sServoArray or INVALID_SERVO if error while attach() or if detached.
Definition: ServoEasing.h:677
ServoEasing::setSpeed
void setSpeed(uint_fast16_t aDegreesPerSecond)
Definition: ServoEasing.hpp:779
ServoEasing::isMovingAndCallYield
bool isMovingAndCallYield() __attribute__((deprecated("Replaced by isMoving(). Often better to use areInterruptsActive() instead.")))
Call yield here (actually only for ESP8266), so the user do not need to care for it in long running l...
Definition: ServoEasing.hpp:1791
Servo::attach
uint8_t attach(int pin, int min, int max)
EASE_PRECISION_IN
#define EASE_PRECISION_IN
Definition: ServoEasing.h:402
ServoEasing::write
void write(int aTargetDegreeOrMicrosecond)
Tested value of 400 for my PCA9685 expander 10/25 (was effectively 382 us / - 2 %,...
Definition: ServoEasing.hpp:860
setEaseToDForAllServos
bool setEaseToDForAllServos(uint_fast16_t aMillisForMove)
Sets target position using content of ServoEasingNextPositionArray and use aMillisForMove instead of ...
Definition: ServoEasing.hpp:2568
enableServoEasingInterrupt
void enableServoEasingInterrupt()
Timer1 is used for the Arduino Servo library.
Definition: ServoEasing.hpp:2048
resumeWithInterruptsAllServos
void resumeWithInterruptsAllServos()
Definition: ServoEasing.hpp:2611
EASE_SINE_IN
#define EASE_SINE_IN
Definition: ServoEasing.h:368
ServoEasing::CubicEaseIn
static float CubicEaseIn(float aPercentageOfCompletion)
Definition: ServoEasing.hpp:2759
ServoEasing::easeTo
void easeTo(int aTargetDegreeOrMicrosecond)
Definition: ServoEasing.hpp:1146
EASE_FUNCTION_MICROSECONDS_INDICATOR_OFFSET
#define EASE_FUNCTION_MICROSECONDS_INDICATOR_OFFSET
Definition: ServoEasing.h:319
ServoEasing::ElasticEaseIn
static float ElasticEaseIn(float aPercentageOfCompletion)
see: https://easings.net/#easeInOutElastic and https://github.com/warrenm/AHEasing/blob/master/AHEasi...
Definition: ServoEasing.hpp:2797
ServoEasing::QuarticEaseIn
static float QuarticEaseIn(float aPercentageOfCompletion)
Definition: ServoEasing.hpp:2763
MILLIS_IN_ONE_SECOND
#define MILLIS_IN_ONE_SECOND
Definition: ServoEasing.h:44
PCA9685_PRESCALE_REGISTER
#define PCA9685_PRESCALE_REGISTER
Definition: ServoEasing.h:438
ServoEasing::setEasingType
void setEasingType(uint_fast8_t aEasingType)
Definition: ServoEasing.hpp:836