mirror of
https://github.com/esp8266/Arduino.git
synced 2025-07-24 19:42:27 +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:
committed by
GitHub
parent
ea4720b03e
commit
ebda795f34
129
libraries/Servo/src/Servo.cpp
Normal file
129
libraries/Servo/src/Servo.cpp
Normal 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
|
Reference in New Issue
Block a user