1
0
mirror of https://github.com/esp8266/Arduino.git synced 2025-07-27 18:02:17 +03:00

Support multiple tone(), analogWrite(), and Servo (#4640)

Remove and rewrite all the parts of the core/libraries using TIMER1
and consolidate into a single, shared waveform generation interrupt
structure.  Tone, analogWrite(), Servo all now just call into this
shared resource to perform their tasks so are all compatible
and can be used simultaneously.

This setup enables multiple tones, analogWrites, servos, and stepper
motors to be controlled with reasonable accuracy.  It uses both TIMER1
and the internal ESP cycle counter to handle timing of waveform edges.
TIMER1 is used in non-reload mode and only edges cause interrupts.  The
interrupt is started and stopped as required, minimizing overhead when
these features are not being used.

A generic "startWaveform(pin, high-US, low-US, runtime-US)" and
"stopWaveform(pin)" allow for further types of interfaces.  Minimum
high or low period is ~1 us.

Add a tone(float) method, useful when working with lower frequencies.

Fixes #4321.  Fixes 4349.
This commit is contained in:
Earle F. Philhower, III
2018-06-07 18:38:58 -07:00
committed by GitHub
parent ea4720b03e
commit ebda795f34
12 changed files with 599 additions and 840 deletions

View File

@ -0,0 +1,129 @@
/*
Servo library using shared TIMER1 infrastructure
Original Copyright (c) 2015 Michael C. Miller. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#if defined(ESP8266)
#include <Arduino.h>
#include <Servo.h>
#include "core_esp8266_waveform.h"
// similiar to map but will have increased accuracy that provides a more
// symetric api (call it and use result to reverse will provide the original value)
int improved_map(int value, int minIn, int maxIn, int minOut, int maxOut)
{
const int rangeIn = maxIn - minIn;
const int rangeOut = maxOut - minOut;
const int deltaIn = value - minIn;
// fixed point math constants to improve accurancy of divide and rounding
const int fixedHalfDecimal = 1;
const int fixedDecimal = fixedHalfDecimal * 2;
return ((deltaIn * rangeOut * fixedDecimal) / (rangeIn) + fixedHalfDecimal) / fixedDecimal + minOut;
}
//-------------------------------------------------------------------
// Servo class methods
Servo::Servo()
{
_attached = false;
_valueUs = DEFAULT_PULSE_WIDTH;
_minUs = MIN_PULSE_WIDTH;
_maxUs = MAX_PULSE_WIDTH;
}
Servo::~Servo() {
detach();
}
uint8_t Servo::attach(int pin)
{
return attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
}
uint8_t Servo::attach(int pin, uint16_t minUs, uint16_t maxUs)
{
if (!_attached) {
digitalWrite(pin, LOW);
pinMode(pin, OUTPUT);
_pin = pin;
_attached = true;
}
// keep the min and max within 200-3000 us, these are extreme
// ranges and should support extreme servos while maintaining
// reasonable ranges
_maxUs = max((uint16_t)250, min((uint16_t)3000, maxUs));
_minUs = max((uint16_t)200, min(_maxUs, minUs));
write(_valueUs);
return pin;
}
void Servo::detach()
{
if (_attached) {
stopWaveform(_pin);
_attached = false;
digitalWrite(_pin, LOW);
}
}
void Servo::write(int value)
{
// treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
if (value < MIN_PULSE_WIDTH) {
// assumed to be 0-180 degrees servo
value = constrain(value, 0, 180);
// writeMicroseconds will contrain the calculated value for us
// for any user defined min and max, but we must use default min max
value = improved_map(value, 0, 180, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
}
writeMicroseconds(value);
}
void Servo::writeMicroseconds(int value)
{
_valueUs = value;
if (_attached) {
startWaveform(_pin, _valueUs, REFRESH_INTERVAL - _valueUs, 0);
}
}
int Servo::read() // return the value as degrees
{
// read returns the angle for an assumed 0-180, so we calculate using
// the normal min/max constants and not user defined ones
return improved_map(readMicroseconds(), MIN_PULSE_WIDTH, MAX_PULSE_WIDTH, 0, 180);
}
int Servo::readMicroseconds()
{
return _valueUs;
}
bool Servo::attached()
{
return _attached;
}
#endif

View File

@ -1,6 +1,6 @@
/*
Servo.h - Interrupt driven Servo library for Esp8266 using timers
Copyright (c) 2015 Michael C. Miller. All right reserved.
Original Copyright (c) 2015 Michael C. Miller. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
@ -23,13 +23,6 @@
// The servos are pulsed in the background using the value most recently
// written using the write() method.
//
// This library uses timer0 and timer1.
// Note that timer0 may be repurposed when the first servo is attached.
//
// Timers are seized as needed in groups of 12 servos - 24 servos use two
// timers, there are only two timers for the esp8266 so the support stops here
// The sequence used to sieze timers is defined in timers.h
//
// The methods are:
//
// Servo - Class for manipulating servo motors connected to Arduino pins.
@ -58,15 +51,7 @@
#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached
#define REFRESH_INTERVAL 20000 // minumim time to refresh servos in microseconds
// NOTE: to maintain a strict refresh interval the user needs to not exceede 8 servos
#define SERVOS_PER_TIMER 12 // the maximum number of servos controlled by one timer
#define MAX_SERVOS (ServoTimerSequence_COUNT * SERVOS_PER_TIMER)
#if defined(ESP8266)
#include "esp8266/ServoTimers.h"
#else
#if !defined(ESP8266)
#error "This library only supports esp8266 boards."
@ -76,6 +61,7 @@ class Servo
{
public:
Servo();
~Servo();
uint8_t attach(int pin); // attach the given pin to the next free channel, sets pinMode, returns channel number or 0 if failure
uint8_t attach(int pin, uint16_t min, uint16_t max); // as above but also sets min and max values for writes.
void detach();
@ -85,9 +71,11 @@ public:
int readMicroseconds(); // returns current pulse width in microseconds for this servo (was read_us() in first release)
bool attached(); // return true if this servo is attached, otherwise false
private:
uint8_t _servoIndex; // index into the channel data for this servo
bool _attached;
uint8_t _pin;
uint16_t _minUs;
uint16_t _maxUs;
uint16_t _valueUs;
};
#endif

View File

@ -1,308 +0,0 @@
/*
Copyright (c) 2015 Michael C. Miller. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#if defined(ESP8266)
#include <Arduino.h>
#include <Servo.h>
#define INVALID_SERVO 255 // flag indicating an invalid servo index
const uint32_t c_CycleCompensation = 4; // compensation us to trim adjust for digitalWrite delays
#define INVALID_PIN 63 // flag indicating never attached servo
struct ServoInfo {
uint8_t pin : 6; // a pin number from 0 to 62, 63 reserved
uint8_t isActive : 1; // true if this channel is enabled, pin not pulsed if false
uint8_t isDetaching : 1; // true if this channel is being detached, maintains pulse integrity
};
struct ServoState {
ServoInfo info;
volatile uint16_t usPulse;
};
#if !defined (SERVO_EXCLUDE_TIMER0)
ServoTimer0 s_servoTimer0;
#endif
#if !defined (SERVO_EXCLUDE_TIMER1)
ServoTimer1 s_servoTimer1;
#endif
static ServoState s_servos[MAX_SERVOS]; // static array of servo structures
static uint8_t s_servoCount = 0; // the total number of attached s_servos
// inconvenience macros
#define SERVO_INDEX_TO_TIMER(servoIndex) ((ServoTimerSequence)(servoIndex / SERVOS_PER_TIMER)) // returns the timer controlling this servo
#define SERVO_INDEX(timerId, channel) ((timerId * SERVOS_PER_TIMER) + channel) // macro to access servo index by timer and channel
// similiar to map but will have increased accuracy that provides a more
// symetric api (call it and use result to reverse will provide the original value)
//
int improved_map(int value, int minIn, int maxIn, int minOut, int maxOut)
{
const int rangeIn = maxIn - minIn;
const int rangeOut = maxOut - minOut;
const int deltaIn = value - minIn;
// fixed point math constants to improve accurancy of divide and rounding
const int fixedHalfDecimal = 1;
const int fixedDecimal = fixedHalfDecimal * 2;
return ((deltaIn * rangeOut * fixedDecimal) / (rangeIn) + fixedHalfDecimal) / fixedDecimal + minOut;
}
//------------------------------------------------------------------------------
// Interrupt handler template method that takes a class that implements
// a standard set of methods for the timer abstraction
//------------------------------------------------------------------------------
template <class T>
static void Servo_Handler(T* timer) ICACHE_RAM_ATTR;
template <class T>
static void Servo_Handler(T* timer)
{
uint8_t servoIndex;
// clear interrupt
timer->ResetInterrupt();
if (timer->isEndOfCycle()) {
timer->StartCycle();
}
else {
servoIndex = SERVO_INDEX(timer->timerId(), timer->getCurrentChannel());
if (servoIndex < s_servoCount && s_servos[servoIndex].info.isActive) {
// pulse this channel low if activated
digitalWrite(s_servos[servoIndex].info.pin, LOW);
if (s_servos[servoIndex].info.isDetaching) {
s_servos[servoIndex].info.isActive = false;
s_servos[servoIndex].info.isDetaching = false;
}
}
timer->nextChannel();
}
servoIndex = SERVO_INDEX(timer->timerId(), timer->getCurrentChannel());
if (servoIndex < s_servoCount &&
timer->getCurrentChannel() < SERVOS_PER_TIMER) {
timer->SetPulseCompare(timer->usToTicks(s_servos[servoIndex].usPulse) - c_CycleCompensation);
if (s_servos[servoIndex].info.isActive) {
if (s_servos[servoIndex].info.isDetaching) {
// it was active, reset state and leave low
s_servos[servoIndex].info.isActive = false;
s_servos[servoIndex].info.isDetaching = false;
}
else {
// its an active channel so pulse it high
digitalWrite(s_servos[servoIndex].info.pin, HIGH);
}
}
}
else {
if (!isTimerActive(timer->timerId())) {
// no active running channels on this timer, stop the ISR
finISR(timer->timerId());
}
else {
// finished all channels so wait for the refresh period to expire before starting over
// allow a few ticks to ensure the next match is not missed
uint32_t refreshCompare = timer->usToTicks(REFRESH_INTERVAL);
if ((timer->GetCycleCount() + c_CycleCompensation * 2) < refreshCompare) {
timer->SetCycleCompare(refreshCompare - c_CycleCompensation);
}
else {
// at least REFRESH_INTERVAL has elapsed
timer->SetCycleCompare(timer->GetCycleCount() + c_CycleCompensation * 2);
}
}
timer->setEndOfCycle();
}
}
static void handler0() ICACHE_RAM_ATTR;
static void handler0()
{
Servo_Handler<ServoTimer0>(&s_servoTimer0);
}
static void handler1() ICACHE_RAM_ATTR;
static void handler1()
{
Servo_Handler<ServoTimer1>(&s_servoTimer1);
}
static void initISR(ServoTimerSequence timerId)
{
#if !defined (SERVO_EXCLUDE_TIMER0)
if (timerId == ServoTimerSequence_Timer0)
s_servoTimer0.InitInterrupt(&handler0);
#endif
#if !defined (SERVO_EXCLUDE_TIMER1)
if (timerId == ServoTimerSequence_Timer1)
s_servoTimer1.InitInterrupt(&handler1);
#endif
}
static void finISR(ServoTimerSequence timerId) ICACHE_RAM_ATTR;
static void finISR(ServoTimerSequence timerId)
{
#if !defined (SERVO_EXCLUDE_TIMER0)
if (timerId == ServoTimerSequence_Timer0)
s_servoTimer0.StopInterrupt();
#endif
#if !defined (SERVO_EXCLUDE_TIMER1)
if (timerId == ServoTimerSequence_Timer1)
s_servoTimer1.StopInterrupt();
#endif
}
// returns true if any servo is active on this timer
static boolean isTimerActive(ServoTimerSequence timerId) ICACHE_RAM_ATTR;
static boolean isTimerActive(ServoTimerSequence timerId)
{
for (uint8_t channel = 0; channel < SERVOS_PER_TIMER; channel++) {
if (s_servos[SERVO_INDEX(timerId, channel)].info.isActive) {
return true;
}
}
return false;
}
//-------------------------------------------------------------------
// Servo class methods
Servo::Servo()
{
if (s_servoCount < MAX_SERVOS) {
// assign a servo index to this instance
_servoIndex = s_servoCount++;
// store default values
s_servos[_servoIndex].usPulse = DEFAULT_PULSE_WIDTH;
// set default _minUs and _maxUs incase write() is called before attach()
_minUs = MIN_PULSE_WIDTH;
_maxUs = MAX_PULSE_WIDTH;
s_servos[_servoIndex].info.isActive = false;
s_servos[_servoIndex].info.isDetaching = false;
s_servos[_servoIndex].info.pin = INVALID_PIN;
}
else {
_servoIndex = INVALID_SERVO; // too many servos
}
}
uint8_t Servo::attach(int pin)
{
return attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
}
uint8_t Servo::attach(int pin, uint16_t minUs, uint16_t maxUs)
{
ServoTimerSequence timerId;
if (_servoIndex < MAX_SERVOS) {
if (s_servos[_servoIndex].info.pin == INVALID_PIN) {
pinMode(pin, OUTPUT); // set servo pin to output
digitalWrite(pin, LOW);
s_servos[_servoIndex].info.pin = pin;
}
// keep the min and max within 200-3000 us, these are extreme
// ranges and should support extreme servos while maintaining
// reasonable ranges
_maxUs = max((uint16_t)250, min((uint16_t)3000, maxUs));
_minUs = max((uint16_t)200, min(_maxUs, minUs));
// initialize the timerId if it has not already been initialized
timerId = SERVO_INDEX_TO_TIMER(_servoIndex);
if (!isTimerActive(timerId)) {
initISR(timerId);
}
s_servos[_servoIndex].info.isDetaching = false;
s_servos[_servoIndex].info.isActive = true; // this must be set after the check for isTimerActive
}
return _servoIndex;
}
void Servo::detach()
{
if (s_servos[_servoIndex].info.isActive) {
s_servos[_servoIndex].info.isDetaching = true;
}
}
void Servo::write(int value)
{
// treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
if (value < MIN_PULSE_WIDTH) {
// assumed to be 0-180 degrees servo
value = constrain(value, 0, 180);
// writeMicroseconds will contrain the calculated value for us
// for any user defined min and max, but we must use default min max
value = improved_map(value, 0, 180, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
}
writeMicroseconds(value);
}
void Servo::writeMicroseconds(int value)
{
// ensure channel is valid
if ((_servoIndex < MAX_SERVOS)) {
// ensure pulse width is valid
value = constrain(value, _minUs, _maxUs);
s_servos[_servoIndex].usPulse = value;
}
}
int Servo::read() // return the value as degrees
{
// read returns the angle for an assumed 0-180, so we calculate using
// the normal min/max constants and not user defined ones
return improved_map(readMicroseconds(), MIN_PULSE_WIDTH, MAX_PULSE_WIDTH, 0, 180);
}
int Servo::readMicroseconds()
{
unsigned int pulsewidth;
if (_servoIndex != INVALID_SERVO) {
pulsewidth = s_servos[_servoIndex].usPulse;
}
else {
pulsewidth = 0;
}
return pulsewidth;
}
bool Servo::attached()
{
return s_servos[_servoIndex].info.isActive;
}
#endif

View File

@ -1,225 +0,0 @@
/*
Copyright (c) 2015 Michael C. Miller. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
//
// Defines for timer abstractions used with Servo library
//
// ServoTimerSequence enumerates the sequence that the timers should be allocated
// ServoTimerSequence_COUNT indicates how many timers are available.
//
enum ServoTimerSequence {
#if !defined (SERVO_EXCLUDE_TIMER0)
ServoTimerSequence_Timer0,
#endif
#if !defined (SERVO_EXCLUDE_TIMER1)
ServoTimerSequence_Timer1,
#endif
ServoTimerSequence_COUNT
};
#if !defined (SERVO_EXCLUDE_TIMER0)
struct ServoTimer0
{
public:
ServoTimer0()
{
setEndOfCycle();
}
uint32_t usToTicks(uint32_t us) const
{
return (clockCyclesPerMicrosecond() * us); // converts microseconds to tick
}
uint32_t ticksToUs(uint32_t ticks) const
{
return (ticks / clockCyclesPerMicrosecond()); // converts from ticks back to microseconds
}
void InitInterrupt(timercallback handler)
{
timer0_isr_init();
timer0_attachInterrupt(handler);
}
void ResetInterrupt() {}; // timer0 doesn't have a clear interrupt
void StopInterrupt()
{
timer0_detachInterrupt();
}
void SetPulseCompare(uint32_t value)
{
timer0_write(ESP.getCycleCount() + value);
}
void SetCycleCompare(uint32_t value)
{
timer0_write(_cycleStart + value);
}
uint32_t GetCycleCount() const
{
return ESP.getCycleCount() - _cycleStart;
}
void StartCycle()
{
_cycleStart = ESP.getCycleCount();
_currentChannel = 0;
}
int8_t getCurrentChannel() const
{
return _currentChannel;
}
void nextChannel()
{
_currentChannel++;
}
void setEndOfCycle()
{
_currentChannel = -1;
}
bool isEndOfCycle() const
{
return (_currentChannel == -1);
}
ServoTimerSequence timerId() const
{
return ServoTimerSequence_Timer0;
}
private:
volatile uint32_t _cycleStart;
volatile int8_t _currentChannel;
};
#endif
#if !defined (SERVO_EXCLUDE_TIMER1)
#define TIMER1_TICKS_PER_US (APB_CLK_FREQ / 1000000L)
struct ServoTimer1
{
public:
ServoTimer1()
{
setEndOfCycle();
}
uint32_t usToTicks(uint32_t us) const
{
return (TIMER1_TICKS_PER_US / 16 * us); // converts microseconds to tick
}
uint32_t ticksToUs(uint32_t ticks) const
{
return (ticks / TIMER1_TICKS_PER_US * 16); // converts from ticks back to microseconds
}
void InitInterrupt(timercallback handler)
{
timer1_isr_init();
timer1_attachInterrupt(handler);
timer1_enable(TIM_DIV16, TIM_EDGE, TIM_SINGLE);
timer1_write(usToTicks(REFRESH_INTERVAL));
}
void ResetInterrupt() {}; // timer1 doesn't have a clear interrupt
void StopInterrupt()
{
timer1_detachInterrupt();
}
void SetPulseCompare(uint32_t value)
{
_cycleTicks += value;
timer1_write(value);
}
void SetCycleCompare(uint32_t value)
{
if (value <= _cycleTicks)
{
value = 1;
}
else
{
value -= _cycleTicks;
}
timer1_write(value);
}
uint32_t GetCycleCount() const
{
return _cycleTicks;
}
void StartCycle()
{
_cycleTicks = 0;
_currentChannel = 0;
}
int8_t getCurrentChannel() const
{
return _currentChannel;
}
void nextChannel()
{
_currentChannel++;
}
void setEndOfCycle()
{
_currentChannel = -1;
}
bool isEndOfCycle() const
{
return (_currentChannel == -1);
}
ServoTimerSequence timerId() const
{
return ServoTimerSequence_Timer1;
}
private:
volatile uint32_t _cycleTicks;
volatile int8_t _currentChannel;
};
#endif