From 9a63d044414d39644613936595735b926aed9a74 Mon Sep 17 00:00:00 2001 From: Armin Date: Tue, 24 Nov 2020 18:24:42 +0100 Subject: [PATCH] Updated LightWeightServo Library --- README.md | 10 +- .../LightweightServoExample.ino | 58 +++-- src/LightweightServo.cpp | 57 +++-- src/LightweightServo.h | 19 +- src/ServoEasing.cpp | 8 +- src/ServoEasing.h | 205 +++++++++--------- 6 files changed, 211 insertions(+), 146 deletions(-) diff --git a/README.md b/README.md index bd6eeb6..aac2305 100644 --- a/README.md +++ b/README.md @@ -1,7 +1,7 @@ # [ServoEasing](https://github.com/ArminJo/ServoEasing) - move your servo more natural Available as Arduino library "ServoEasing" -### [Version 2.3.2](https://github.com/ArminJo/ServoEasing/releases) +### [Version 2.3.3](https://github.com/ArminJo/ServoEasing/releases) - work in progress [![License: GPL v3](https://img.shields.io/badge/License-GPLv3-blue.svg)](https://www.gnu.org/licenses/gpl-3.0) [![Installation instructions](https://www.ardu-badge.com/badge/ServoEasing.svg?)](https://www.ardu-badge.com/ServoEasing) @@ -29,7 +29,7 @@ For instructions how to enable these alternatives see [Compile options / macros] - Allow to specify an arbitrary mapping between degrees and microseconds by `attach(int aPin, int aMicrosecondsForServoLowDegree, int aMicrosecondsForServoHighDegree, int aServoLowDegree, int aServoHighDegree)`. - **Servo speed** can be specified in **degree per second** or **milliseconds** for the complete move. -## [API](https://github.com/ArminJo/ServoEasing/blob/master/src/ServoEasing.h#L428) +## [API](https://github.com/ArminJo/ServoEasing/blob/master/src/ServoEasing.h#L328) ## Usage Just call **myServo.startEaseTo()** instead of **myServo.write()** and you are done. Or if you want to wait (blocking) until servo has arrived, use **myServo.easeTo()**.
@@ -218,7 +218,7 @@ On **AVR** Timer1 is used for the Arduino Servo library. To have non blocking ea ## Adding a new platform / board If timer support is available for a platform the library can be ported by adding code for the Timer20ms like is was done for ESP and STM.
To add a new platform, the following steps have to be performed: -1. If the new platform has an **Arduino compatible Servo library**, fine, otherwise include the one required for this platform like it is done for ESP32 [here](src/ServoEasing.h#L92). +1. If the new platform has an **Arduino compatible Servo library**, fine, otherwise include the one required for this platform like it is done for ESP32 [here](src/ServoEasing.h#L83). 2. You need a **20ms interrupt source** providing the functions enableServoEasingInterrupt() and (optional) disableServoEasingInterrupt(). Extend these functions with code for the new platform. Place includes and timer definitions at top of *ServoEasing.cpp*. 3. If your interrupt source requires an ISR (Interrupt Service Routine) place it after disableServoEasingInterrupt() where all the other ISR are located. 4. To test the new platform, you may want to enable **TRACE output** by commenting out the line `#define TRACE` in *ServoEasing.cpp* @@ -232,6 +232,10 @@ If you see strange behavior, you can open the library file *ServoEasing.h* and c This will print internal information visible in the Arduino *Serial Monitor* which may help finding the reason for it. # Revision History +### Version 2.3.3 - work in progress +- DegreeToMicrosecondsOrUnits() does not convert values >= 400 in order to support Microseconds instead of degrees as function arguments. +- Improved LightweightServo API. + ### Version 2.3.2 - Removed blocking wait for ATmega32U4 Serial in examples. - Improved output for Arduino Serial Plotter. diff --git a/examples/LightweightServoExample/LightweightServoExample.ino b/examples/LightweightServoExample/LightweightServoExample.ino index 65fd6b9..bf0876a 100644 --- a/examples/LightweightServoExample/LightweightServoExample.ino +++ b/examples/LightweightServoExample/LightweightServoExample.ino @@ -38,40 +38,62 @@ void setup() { Serial.println(F("Using library version " VERSION_LIGHTWEIGHT_SERVO)); #endif // no initialization required for LightweightServo :-) + // or use manual initialization (and compiler macro "DISABLE_SERVO_TIMER_AUTO_INITIALIZE") to save additional 60 bytes program space + // initLightweightServoPin9(); + delay(3000); } void loop() { #if defined (__AVR_ATmega328P__) || defined (__AVR_ATmega328__) || defined (__AVR_ATmega328PB__) /* - * Let the servo at pin 9 swipe from 0 to 180 and back to 90 degree + * Let the servo at pin 9 + 10 swipe from 180 to 0 and back to 90 degree */ - write9(0); - delay(1500); + Serial.println(F("Move to 180 degree")); write9(180); - delay(1000); + write10(180); + delay(2000); + + Serial.println(F("Move to 90 degree")); write9(90); - delay(1000); + write10(90); + delay(2000); - /* - * Now move servo at pin 10 - */ + Serial.println(F("Move to 0 degree")); + write9(0); write10(0); - delay(1500); - write10(180); - delay(1000); + delay(2000); + + Serial.println(F("Move to 900 degree")); + write9(90); write10(90); - delay(1000); + delay(2000); + + Serial.println(F("Move back to 180 degree")); + write9(180); + write10(180); + delay(2000); + Serial.println(); /* - * Move both servos to 45 degree using microseconds as parameter + * Move both servos to 135 and 45 degree using microseconds as parameter */ - Serial.print(F("45 degree = ")); - Serial.print(MicrosecondsToDegreeLightweightServo(45)); + Serial.print(F("Move to 135 degree = ")); + Serial.print(DegreeToMicrosecondsLightweightServo(135)); + Serial.println(F(" micro seconds")); + writeMicroseconds9(DegreeToMicrosecondsLightweightServo(135)); + writeMicroseconds10(DegreeToMicrosecondsLightweightServo(135)); + Serial.println(); + delay(2000); + + Serial.print(F("Move to 45 degree = ")); + Serial.print(DegreeToMicrosecondsLightweightServo(45)); Serial.println(F(" micro seconds")); - writeMicroseconds9(1008); - writeMicroseconds10(1008); + writeMicroseconds9(DegreeToMicrosecondsLightweightServo(45)); + writeMicroseconds10(DegreeToMicrosecondsLightweightServo(45)); + + delay(5000); + #else Serial.println(F("LightweightServoExample works only for ATmega328*")); #endif - delay(5000); } diff --git a/src/LightweightServo.cpp b/src/LightweightServo.cpp index 5b7e79e..cd0e889 100644 --- a/src/LightweightServo.cpp +++ b/src/LightweightServo.cpp @@ -53,43 +53,66 @@ void initLightweightServoPin9And10() { DDRB |= _BV(DDB1) | _BV(DDB2); // set pins OC1A = PortB1 -> PIN 9 and OC1B = PortB2 -> PIN 10 to output direction TCCR1A = _BV(COM1A1) | _BV(COM1B1) | _BV(WGM11); // FastPWM Mode mode TOP (20 ms) determined by ICR1 - non-inverting Compare Output mode OC1A+OC1B TCCR1B = _BV(WGM13) | _BV(WGM12) | _BV(CS11); // set prescaler to 8, FastPWM mode mode bits WGM13 + WGM12 - ICR1 = ISR1_COUNT_FOR_20_MILLIS; // set period to 20 ms + ICR1 = ISR1_COUNT_FOR_20_MILLIS; // set period to 20 ms // do not set counter here, since with counter = 0 (default) no output signal is generated. } /* * Use 16 bit timer1 for generating 2 servo signals entirely by hardware without any interrupts. * Use FastPWM mode and generate pulse at start of the 20 ms period - * The 2 servo signals are tied to pin 9 and 10 of an 328. + * The 2 servo signals are tied to pin 9 and 10 of an ATMega328. * Attention - the selected pin is set to OUTPUT here! * 54 bytes code size */ void initLightweightServoPin9_10(bool aUsePin9, bool aUsePin10) { uint8_t tNewTCCR1A = TCCR1A & (_BV(COM1A1) | _BV(COM1B1)); // keep existing COM1A1 and COM1B1 settings - tNewTCCR1A |= _BV(WGM11); // FastPWM Mode mode TOP (20 ms) determined by ICR1 + tNewTCCR1A |= _BV(WGM11); // FastPWM Mode mode TOP (20 ms) determined by ICR1 if (aUsePin9) { - DDRB |= _BV(DDB1); // set OC1A = PortB1 -> PIN 9 to output direction - tNewTCCR1A |= _BV(COM1A1); // non-inverting Compare Output mode OC1A - } + DDRB |= _BV(DDB1); // set OC1A = PortB1 -> PIN 9 to output direction + tNewTCCR1A |= _BV(COM1A1); // non-inverting Compare Output mode OC1A + OCR1A = 0xFFFF; // Set counter > ICR1 here, to avoid output signal generation. + } if (aUsePin10) { - DDRB |= _BV(DDB2); // set OC1B = PortB2 -> PIN 10 to output direction - tNewTCCR1A |= _BV(COM1B1); // non-inverting Compare Output mode OC1B + DDRB |= _BV(DDB2); // set OC1B = PortB2 -> PIN 10 to output direction + tNewTCCR1A |= _BV(COM1B1); // non-inverting Compare Output mode OC1B + OCR1B = 0xFFFF; // Set counter > ICR1 here, to avoid output signal generation. } TCCR1A = tNewTCCR1A; - TCCR1B = _BV(WGM13) | _BV(WGM12) | _BV(CS11); // set prescaler to 8, FastPWM Mode mode bits WGM13 + WGM12 - ICR1 = ISR1_COUNT_FOR_20_MILLIS; // set period to 20 ms - // Do not set counter here, since with counter = 0 (default) no output signal is generated now. + TCCR1B = _BV(WGM13) | _BV(WGM12) | _BV(CS11); // set prescaler to 8, FastPWM Mode mode bits WGM13 + WGM12 + ICR1 = ISR1_COUNT_FOR_20_MILLIS; // set period to 20 ms +} + +/* + * Disables Pin 10! + */ +void initLightweightServoPin9() { + DDRB |= _BV(DDB1); // set OC1A = PortB1 -> PIN 9 to output direction + TCCR1A = _BV(WGM11) | _BV(COM1A1); // FastPWM Mode mode TOP (20 ms) determined by ICR1, non-inverting Compare Output mode OC1A + TCCR1B = _BV(WGM13) | _BV(WGM12) | _BV(CS11); // set prescaler to 8, FastPWM Mode mode bits WGM13 + WGM12 + ICR1 = ISR1_COUNT_FOR_20_MILLIS; // set period to 20 ms + OCR1A = 0xFFFF; // Set counter > ICR1 here, to avoid output signal generation. +} +/* + * Disables Pin 9! + */ +void initLightweightServoPin10() { + DDRB |= _BV(DDB2); // set OC1B = PortB2 -> PIN 10 to output direction + TCCR1A = _BV(WGM11) | _BV(COM1B1); // FastPWM Mode mode TOP (20 ms) determined by ICR1, non-inverting Compare Output mode OC1B + TCCR1B = _BV(WGM13) | _BV(WGM12) | _BV(CS11); // set prescaler to 8, FastPWM Mode mode bits WGM13 + WGM12 + ICR1 = ISR1_COUNT_FOR_20_MILLIS; // set period to 20 ms + OCR1B = 0xFFFF; // Set counter > ICR1 here, to avoid output signal generation. } -void deinitLightweightServoPin9_10(bool aUsePin9) { +void deinitLightweightServoPin9_10(bool aUsePin9, bool aUsePin10) { if (aUsePin9) { - DDRB &= ~(_BV(DDB1)); // set OC1A = PortB1 -> PIN 9 to input direction - TCCR1A &= ~(_BV(COM1A1)); // disable non-inverting Compare Output mode OC1A - } else { - DDRB &= ~(_BV(DDB2)); // set OC1B = PortB2 -> PIN 10 to input direction - TCCR1A &= ~(_BV(COM1B1)); // disable non-inverting Compare Output mode OC1B + DDRB &= ~(_BV(DDB1)); // set OC1A = PortB1 -> PIN 9 to input direction + TCCR1A &= ~(_BV(COM1A1)); // disable non-inverting Compare Output mode OC1A + } + if (aUsePin10) { + DDRB &= ~(_BV(DDB2)); // set OC1B = PortB2 -> PIN 10 to input direction + TCCR1A &= ~(_BV(COM1B1)); // disable non-inverting Compare Output mode OC1B } } diff --git a/src/LightweightServo.h b/src/LightweightServo.h index e84b39b..9084063 100644 --- a/src/LightweightServo.h +++ b/src/LightweightServo.h @@ -1,7 +1,7 @@ /* * LightweightServo.h * - * Copyright (C) 2019 Armin Joachimsmeyer + * Copyright (C) 2019-2020 Armin Joachimsmeyer * armin.joachimsmeyer@gmail.com * * This file is part of ServoEasing https://github.com/ArminJo/ServoEasing. @@ -26,9 +26,9 @@ #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega328__) -#define VERSION_LIGHTWEIGHT_SERVO "1.0.0" +#define VERSION_LIGHTWEIGHT_SERVO "1.1.0" #define VERSION_LIGHTWEIGHT_SERVO_MAJOR 1 -#define VERSION_LIGHTWEIGHT_SERVO_MINOR 0 +#define VERSION_LIGHTWEIGHT_SERVO_MINOR 1 #include @@ -36,7 +36,6 @@ * Commenting out this saves 70 bytes flash memory. You must then use the init function initLightweightServoPin9And10() manually. */ //#define DISABLE_SERVO_TIMER_AUTO_INITIALIZE - #define ISR1_COUNT_FOR_20_MILLIS 40000 // you can modify this if you have servos which accept a higher rate /* @@ -44,8 +43,10 @@ * Uses timer1 and Pin 9 + 10 as output */ void initLightweightServoPin9And10(); -void initLightweightServoPin9_10(bool aUsePin9 = true, bool aUsePin10 = true); -void deinitLightweightServoPin9_10(bool aUsePin9); +void initLightweightServoPin9(); // Disables Pin 10! +void initLightweightServoPin10(); // Disables Pin 9! +void initLightweightServoPin9_10(bool aUsePin9, bool aUsePin10); +void deinitLightweightServoPin9_10(bool aUsePin9, bool aUsePin10); void setLightweightServoPulseMicrosFor0And180Degree(int aMicrosecondsForServo0Degree, int a180DegreeValue); void setLightweightServoRefreshRate(unsigned int aRefreshPeriodMicroseconds); @@ -66,6 +67,12 @@ int DegreeToMicrosecondsLightweightServo(int aDegree); int MicrosecondsToDegreeLightweightServo(int aMicroseconds); #endif // AVR_ATmega328 + +/* + * Version 1.1.0 - 11/2020 + * - Improved API. + */ + #endif // LIGHTWEIGHT_SERVO_H_ #pragma once diff --git a/src/ServoEasing.cpp b/src/ServoEasing.cpp index a57e8d2..746e154 100644 --- a/src/ServoEasing.cpp +++ b/src/ServoEasing.cpp @@ -400,7 +400,7 @@ void ServoEasing::detach() { setPWM(0); // set signal fully off # endif #elif defined(USE_LEIGHTWEIGHT_SERVO_LIB) - deinitLightweightServoPin9_10(mServoPin == 9); // disable output and change to input + deinitLightweightServoPin9_10(mServoPin == 9, mServoPin == 10); // disable output and change to input #else Servo::detach(); #endif @@ -595,7 +595,11 @@ int ServoEasing::MicrosecondsOrUnitsToDegree(int aMicrosecondsOrUnits) { */ int ServoEasing::DegreeToMicrosecondsOrUnits(int aDegree) { // For microseconds and PCA9685 units: - return map(aDegree, 0, 180, mServo0DegreeMicrosecondsOrUnits, mServo180DegreeMicrosecondsOrUnits); + if (aDegree < 400) { + return map(aDegree, 0, 180, mServo0DegreeMicrosecondsOrUnits, mServo180DegreeMicrosecondsOrUnits); + } else { + return aDegree; + } } /** diff --git a/src/ServoEasing.h b/src/ServoEasing.h index 192f989..6449be7 100644 --- a/src/ServoEasing.h +++ b/src/ServoEasing.h @@ -24,9 +24,10 @@ #ifndef SERVOEASING_H_ #define SERVOEASING_H_ -#define VERSION_SERVO_EASING "2.3.2" +#define VERSION_SERVO_EASING "2.3.3" #define VERSION_SERVO_EASING_MAJOR 2 #define VERSION_SERVO_EASING_MINOR 3 +// The change log is at the bottom of the file // @formatter:off /* ***************************************************************************************************************************** @@ -183,105 +184,6 @@ // @formatter:on -/* - * Version 2.3.2 - 9/2020 - * - Removed blocking wait for ATmega32U4 Serial in examples. - * - Improved output for Arduino Serial Plotter. - * - * Version 2.3.1 - 9/2020 - * - Fixed wrong timer selection for `STM32F1xx` / `ARDUINO_ARCH_STM32`. - * - Documentation. - * - * Version 2.3.0 - 7/2020 - * - Fixed EASE_LINEAR formula bug introduced with 2.0.0 for 32 bit CPU's. - * - Added `stop()`, `continueWithInterrupts()` and `continueWithoutInterrupts()` functions. - * - * Version 2.2.0 - 7/2020 - * - ATmega4809 (Uno WiFi Rev 2, Nano Every) support. - * - Corrected position of macro for MAX_EASING_SERVOS. - * - * Version 2.1.1 - 6/2020 - * - Fixed bug in detach of first servo. - * - * Version 2.1.0 - 6/2020 - * - Teensy support. - * - * Version 2.0.0 - 5/2020 - * - `PCA9685_Expander` and standard Servos can be controlled simultaneously by defining `USE_SERVO_LIB`. - * - Changed some types to _fast types - * - Standardize pins for all examples - * - * Version 1.6.1 - 5/2020 - * - Fix bug for **Arduino SAMD** boards. - * - * Version 1.6.0 - 4/2020 - * - Added support of Apollo3 boards. - * - Print library version in examples. - * - * Version 1.5.2 - 3/2020 - * - More examples using `areInterruptsActive()`. - * - Added support of Arduino SAMD boards. - * - * Version 1.5.1 - 3/2020 - * - Added support for STM32 cores of Arduino Board manager. Seen in the Arduino IDE as "Generic STM32F1 series" from STM32 Boards. - * - Inserted missing `Wire.begin()` in setup of `PCA9685_Expander` example. - * - In `isMovingAndCallYield()` yield() only called/required for an ESP8266. - * - New function `areInterruptsActive()`, especially for ESP32. - * - * Version 1.5.0 - 2/2020 - * - Use type `Print *` instead of `Stream *`. - * - New LightweightServoExample. - * - Added function `delayAndUpdateAndWaitForAllServosToStop()`. - * - Added Arduino Due support by using timer 8. - * - New PCA9685_ExpanderFor32Servos example. - * - * Version 1.4.3 - 12/2019 - * - Improved detach() handling. - * - Initialize mSpeed explicitly to 0 in constructor. On an ESP8266 it was NOT initialized to 0 :-(. - * - * Version 1.4.2 - 11/2019 - * - Improved INVALID_SERVO handling. - * - Speed 0 (not initialized) handling. - * - Fixed bug in ThreeServos example. - * - * Version 1.4.1 - 11/2019 - * - Improved documentation and definitions for continuous rotating servo. Thanks to Eebel! - * - Improved support and documentation for generating Arduino Serial Plotter output. - * - Support of STM32F1 / BluePill boards. - * - * Version 1.4.0 - 11/2019 - * - setTrim has additional parameter 'doWrite' which is default 'false' in contrast to older versions, where a write was always performed. - * - New attach( aPin, aMicrosecondsForServoLowDegree, aMicrosecondsForServoHighDegree, aServoLowDegree, aServoHighDegree) function for arbitrary mapping of servo degree to servo pulse width. - * - Order of Servos in 'sServoArray[]' now depends from order of calling attach() and not from order of declaration. - * - New example for continuous rotating servo. - * - Support for multiple PCA9685 expander. - * - * Version 1.3.1 - 6/2019 - * - Added detach() function. - * - * Version 1.3.0 - 6/2019 - * - Added ESP32 support by using ESP32Servo.h and Ticker.h instead of Servo.h timer interrupts. - * - Changed degree parameter and values from uint8_t to integer to support operating a servo from -90 to + 90 degree with 90 degree trim. - * - RobotArmControl + QuadrupedControl examples refactored. - * - Extended SpeedTest example. Now also able to change the width of the refresh period. - * - Changed "while" to "for" loops to avoid a gcc 7.3.0 atmel6.3.1 bug. - * - * Version 1.2 - 5/2019 - * - Added ESP8266 support by using Ticker instead of timer interrupts for ESP. - * - AsymetricEasing example overhauled. - * - * Version 1.1 - 4/2019 - * - corrected sine, circular, back and elastic IN functions. - * - easeTo() and write() store their degree parameter now also in sServoNextPositionArray. - * - added setSpeed(), getSpeed(), setSpeedForAllServos(). - * - added easeTo(uint8_t aDegree) and setEaseTo(uint8_t aDegree). - * - added setEaseToForAllServos(), setEaseToForAllServosSynchronizeAndStartInterrupt(), synchronizeAndEaseToArrayPositions(). - * - added getEndMicrosecondsOrUnits(), getDeltaMicrosecondsOrUnits(). - * - added setDegreeForAllServos(uint8_t aNumberOfValues, va_list * aDegreeValues),setDegreeForAllServos(uint8_t aNumberOfValues, ...). - * - added compile switch PROVIDE_ONLY_LINEAR_MOVEMENT to save additional 1500 bytes FLASH if enabled. - * - added convenience function clipDegreeSpecial(). - */ - #define DEFAULT_MICROSECONDS_FOR_0_DEGREE 544 #define DEFAULT_MICROSECONDS_FOR_180_DEGREE 2400 // Approximately 10 microseconds per degree @@ -612,6 +514,109 @@ extern float (*sEaseFunctionArray[])(float aPercentageOfCompletion); #define STR_HELPER(x) #x #define STR(x) STR_HELPER(x) +/* + * Version 2.3.3 - 11/2020 + * - DegreeToMicrosecondsOrUnits() does not convert values >= 400 in order to support Microseconds instead of degrees as function arguments. + * - Improved LightweightServo API. + * + * Version 2.3.2 - 9/2020 + * - Removed blocking wait for ATmega32U4 Serial in examples. + * - Improved output for Arduino Serial Plotter. + * + * Version 2.3.1 - 9/2020 + * - Fixed wrong timer selection for `STM32F1xx` / `ARDUINO_ARCH_STM32`. + * - Documentation. + * + * Version 2.3.0 - 7/2020 + * - Fixed EASE_LINEAR formula bug introduced with 2.0.0 for 32 bit CPU's. + * - Added `stop()`, `continueWithInterrupts()` and `continueWithoutInterrupts()` functions. + * + * Version 2.2.0 - 7/2020 + * - ATmega4809 (Uno WiFi Rev 2, Nano Every) support. + * - Corrected position of macro for MAX_EASING_SERVOS. + * + * Version 2.1.1 - 6/2020 + * - Fixed bug in detach of first servo. + * + * Version 2.1.0 - 6/2020 + * - Teensy support. + * + * Version 2.0.0 - 5/2020 + * - `PCA9685_Expander` and standard Servos can be controlled simultaneously by defining `USE_SERVO_LIB`. + * - Changed some types to _fast types + * - Standardize pins for all examples + * + * Version 1.6.1 - 5/2020 + * - Fix bug for **Arduino SAMD** boards. + * + * Version 1.6.0 - 4/2020 + * - Added support of Apollo3 boards. + * - Print library version in examples. + * + * Version 1.5.2 - 3/2020 + * - More examples using `areInterruptsActive()`. + * - Added support of Arduino SAMD boards. + * + * Version 1.5.1 - 3/2020 + * - Added support for STM32 cores of Arduino Board manager. Seen in the Arduino IDE as "Generic STM32F1 series" from STM32 Boards. + * - Inserted missing `Wire.begin()` in setup of `PCA9685_Expander` example. + * - In `isMovingAndCallYield()` yield() only called/required for an ESP8266. + * - New function `areInterruptsActive()`, especially for ESP32. + * + * Version 1.5.0 - 2/2020 + * - Use type `Print *` instead of `Stream *`. + * - New LightweightServoExample. + * - Added function `delayAndUpdateAndWaitForAllServosToStop()`. + * - Added Arduino Due support by using timer 8. + * - New PCA9685_ExpanderFor32Servos example. + * + * Version 1.4.3 - 12/2019 + * - Improved detach() handling. + * - Initialize mSpeed explicitly to 0 in constructor. On an ESP8266 it was NOT initialized to 0 :-(. + * + * Version 1.4.2 - 11/2019 + * - Improved INVALID_SERVO handling. + * - Speed 0 (not initialized) handling. + * - Fixed bug in ThreeServos example. + * + * Version 1.4.1 - 11/2019 + * - Improved documentation and definitions for continuous rotating servo. Thanks to Eebel! + * - Improved support and documentation for generating Arduino Serial Plotter output. + * - Support of STM32F1 / BluePill boards. + * + * Version 1.4.0 - 11/2019 + * - setTrim has additional parameter 'doWrite' which is default 'false' in contrast to older versions, where a write was always performed. + * - New attach( aPin, aMicrosecondsForServoLowDegree, aMicrosecondsForServoHighDegree, aServoLowDegree, aServoHighDegree) function for arbitrary mapping of servo degree to servo pulse width. + * - Order of Servos in 'sServoArray[]' now depends from order of calling attach() and not from order of declaration. + * - New example for continuous rotating servo. + * - Support for multiple PCA9685 expander. + * + * Version 1.3.1 - 6/2019 + * - Added detach() function. + * + * Version 1.3.0 - 6/2019 + * - Added ESP32 support by using ESP32Servo.h and Ticker.h instead of Servo.h timer interrupts. + * - Changed degree parameter and values from uint8_t to integer to support operating a servo from -90 to + 90 degree with 90 degree trim. + * - RobotArmControl + QuadrupedControl examples refactored. + * - Extended SpeedTest example. Now also able to change the width of the refresh period. + * - Changed "while" to "for" loops to avoid a gcc 7.3.0 atmel6.3.1 bug. + * + * Version 1.2 - 5/2019 + * - Added ESP8266 support by using Ticker instead of timer interrupts for ESP. + * - AsymetricEasing example overhauled. + * + * Version 1.1 - 4/2019 + * - corrected sine, circular, back and elastic IN functions. + * - easeTo() and write() store their degree parameter now also in sServoNextPositionArray. + * - added setSpeed(), getSpeed(), setSpeedForAllServos(). + * - added easeTo(uint8_t aDegree) and setEaseTo(uint8_t aDegree). + * - added setEaseToForAllServos(), setEaseToForAllServosSynchronizeAndStartInterrupt(), synchronizeAndEaseToArrayPositions(). + * - added getEndMicrosecondsOrUnits(), getDeltaMicrosecondsOrUnits(). + * - added setDegreeForAllServos(uint8_t aNumberOfValues, va_list * aDegreeValues),setDegreeForAllServos(uint8_t aNumberOfValues, ...). + * - added compile switch PROVIDE_ONLY_LINEAR_MOVEMENT to save additional 1500 bytes FLASH if enabled. + * - added convenience function clipDegreeSpecial(). + */ + #endif /* SERVOEASING_H_ */ #pragma once