Skip to content

Commit

Permalink
Updated LightWeightServo Library
Browse files Browse the repository at this point in the history
  • Loading branch information
ArminJo committed Nov 24, 2020
1 parent be94356 commit 9a63d04
Show file tree
Hide file tree
Showing 6 changed files with 211 additions and 146 deletions.
10 changes: 7 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
@@ -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)
Expand Down Expand Up @@ -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()**.<br/>
Expand Down Expand Up @@ -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.<br/>
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*
Expand All @@ -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.
Expand Down
58 changes: 40 additions & 18 deletions examples/LightweightServoExample/LightweightServoExample.ino
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
57 changes: 40 additions & 17 deletions src/LightweightServo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
}
}

Expand Down
19 changes: 13 additions & 6 deletions src/LightweightServo.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
/*
* LightweightServo.h
*
* Copyright (C) 2019 Armin Joachimsmeyer
* Copyright (C) 2019-2020 Armin Joachimsmeyer
* [email protected]
*
* This file is part of ServoEasing https://github.com/ArminJo/ServoEasing.
Expand All @@ -26,26 +26,27 @@

#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 <stdint.h>

/*
* 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

/*
* Lightweight servo library
* 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);
Expand All @@ -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
8 changes: 6 additions & 2 deletions src/ServoEasing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
}
}

/**
Expand Down
Loading

0 comments on commit 9a63d04

Please sign in to comment.