Commit 4e1237f1 authored by Frank Radzio 's avatar Frank Radzio

Code Optimierung

parent 6bce3589
name=Servo
version=1.1.1
version=1.1.3
author=Michael Margolis, Arduino
maintainer=Arduino <info@arduino.cc>
sentence=Allows Arduino boards to control a variety of servo motors. For all Arduino boards.
sentence=Allows Arduino/Genuino boards to control a variety of servo motors.
paragraph=This library can control a great number of servos.<br />It makes careful use of timers: the library can control 12 servos using only 1 timer.<br />On the Arduino Due you can control up to 60 servos.<br />
category=Device Control
url=http://www.arduino.cc/en/Reference/Servo
architectures=avr,sam,samd
architectures=avr,megaAVR,sam,samd,nrf52,stm32f4
......@@ -65,8 +65,14 @@
#include "sam/ServoTimers.h"
#elif defined(ARDUINO_ARCH_SAMD)
#include "samd/ServoTimers.h"
#elif defined(ARDUINO_ARCH_STM32F4)
#include "stm32f4/ServoTimers.h"
#elif defined(ARDUINO_ARCH_NRF52)
#include "nrf52/ServoTimers.h"
#elif defined(ARDUINO_ARCH_MEGAAVR)
#include "megaavr/ServoTimers.h"
#else
#error "This library only supports boards with an AVR, SAM or SAMD processor."
#error "This library only supports boards with an AVR, SAM, SAMD, NRF52 or STM32F4 processor."
#endif
#define Servo_VERSION 2 // software version of this library
......@@ -81,6 +87,8 @@
#define INVALID_SERVO 255 // flag indicating an invalid servo index
#if !defined(ARDUINO_ARCH_STM32F4)
typedef struct {
uint8_t nbr :6 ; // a pin number from 0 to 63
uint8_t isActive :1 ; // true if this channel is enabled, pin not pulsed if false
......@@ -110,3 +118,4 @@ private:
};
#endif
#endif
......@@ -202,7 +202,8 @@ static void finISR(timer16_Sequence_t timer)
timerDetach(TIMER3OUTCOMPAREA_INT);
}
#else
//For arduino - in future: call here to a currently undefined function to reset the timer
//For arduino - in future: call here to a currently undefined function to reset the timer
(void) timer; // squash "unused parameter 'timer' [-Wunused-parameter]" warning
#endif
}
......
......@@ -47,7 +47,7 @@ typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t;
#define _useTimer1
typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t;
#elif defined(__AVR_ATmega128__) ||defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
#elif defined(__AVR_ATmega128__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega2561__)
#define _useTimer3
#define _useTimer1
typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t;
......
#if defined(ARDUINO_ARCH_MEGAAVR)
#include <Arduino.h>
#include <Servo.h>
#define usToTicks(_us) ((clockCyclesPerMicrosecond() / 16 * _us) / 4) // converts microseconds to tick
#define ticksToUs(_ticks) (((unsigned) _ticks * 16) / (clockCyclesPerMicrosecond() / 4)) // converts from ticks back to microseconds
#define TRIM_DURATION 5 // compensation ticks to trim adjust for digitalWrite delays
static servo_t servos[MAX_SERVOS]; // static array of servo structures
uint8_t ServoCount = 0; // the total number of attached servos
static volatile int8_t currentServoIndex[_Nbr_16timers]; // index for the servo being pulsed for each timer (or -1 if refresh interval)
// convenience macros
#define SERVO_INDEX_TO_TIMER(_servo_nbr) ((timer16_Sequence_t)(_servo_nbr / SERVOS_PER_TIMER)) // returns the timer controlling this servo
#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % SERVOS_PER_TIMER) // returns the index of the servo on this timer
#define SERVO_INDEX(_timer,_channel) ((_timer*SERVOS_PER_TIMER) + _channel) // macro to access servo index by timer and channel
#define SERVO(_timer,_channel) (servos[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel
#define SERVO_MIN() (MIN_PULSE_WIDTH - this->min * 4) // minimum value in uS for this servo
#define SERVO_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo
void ServoHandler(int timer)
{
if (currentServoIndex[timer] < 0) {
// Write compare register
_timer->CCMP = 0;
} else {
if (SERVO_INDEX(timer, currentServoIndex[timer]) < ServoCount && SERVO(timer, currentServoIndex[timer]).Pin.isActive == true) {
digitalWrite(SERVO(timer, currentServoIndex[timer]).Pin.nbr, LOW); // pulse this channel low if activated
}
}
// Select the next servo controlled by this timer
currentServoIndex[timer]++;
if (SERVO_INDEX(timer, currentServoIndex[timer]) < ServoCount && currentServoIndex[timer] < SERVOS_PER_TIMER) {
if (SERVO(timer, currentServoIndex[timer]).Pin.isActive == true) { // check if activated
digitalWrite(SERVO(timer, currentServoIndex[timer]).Pin.nbr, HIGH); // it's an active channel so pulse it high
}
// Get the counter value
uint16_t tcCounterValue = 0; //_timer->CCMP;
_timer->CCMP = (uint16_t) (tcCounterValue + SERVO(timer, currentServoIndex[timer]).ticks);
}
else {
// finished all channels so wait for the refresh period to expire before starting over
// Get the counter value
uint16_t tcCounterValue = _timer->CCMP;
if (tcCounterValue + 4UL < usToTicks(REFRESH_INTERVAL)) { // allow a few ticks to ensure the next OCR1A not missed
_timer->CCMP = (uint16_t) usToTicks(REFRESH_INTERVAL);
}
else {
_timer->CCMP = (uint16_t) (tcCounterValue + 4UL); // at least REFRESH_INTERVAL has elapsed
}
currentServoIndex[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
}
/* Clear flag */
_timer->INTFLAGS = TCB_CAPT_bm;
}
#if defined USE_TIMERB0
ISR(TCB0_INT_vect)
#elif defined USE_TIMERB1
ISR(TCB1_INT_vect)
#elif defined USE_TIMERB2
ISR(TCB2_INT_vect)
#endif
{
ServoHandler(0);
}
static void initISR(timer16_Sequence_t timer)
{
//TCA0.SINGLE.CTRLA = (TCA_SINGLE_CLKSEL_DIV16_gc) | (TCA_SINGLE_ENABLE_bm);
_timer->CTRLA = TCB_CLKSEL_CLKTCA_gc;
// Timer to Periodic interrupt mode
// This write will also disable any active PWM outputs
_timer->CTRLB = TCB_CNTMODE_INT_gc;
// Enable interrupt
_timer->INTCTRL = TCB_CAPTEI_bm;
// Enable timer
_timer->CTRLA |= TCB_ENABLE_bm;
}
static void finISR(timer16_Sequence_t timer)
{
// Disable interrupt
_timer->INTCTRL = 0;
}
static boolean isTimerActive(timer16_Sequence_t timer)
{
// returns true if any servo is active on this timer
for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) {
if(SERVO(timer,channel).Pin.isActive == true)
return true;
}
return false;
}
/****************** end of static functions ******************************/
Servo::Servo()
{
if (ServoCount < MAX_SERVOS) {
this->servoIndex = ServoCount++; // assign a servo index to this instance
servos[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values
} else {
this->servoIndex = INVALID_SERVO; // too many servos
}
}
uint8_t Servo::attach(int pin)
{
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
}
uint8_t Servo::attach(int pin, int min, int max)
{
timer16_Sequence_t timer;
if (this->servoIndex < MAX_SERVOS) {
pinMode(pin, OUTPUT); // set servo pin to output
servos[this->servoIndex].Pin.nbr = pin;
// todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128
this->min = (MIN_PULSE_WIDTH - min)/4; //resolution of min/max is 4 uS
this->max = (MAX_PULSE_WIDTH - max)/4;
// initialize the timer if it has not already been initialized
timer = SERVO_INDEX_TO_TIMER(servoIndex);
if (isTimerActive(timer) == false) {
initISR(timer);
}
servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
}
return this->servoIndex;
}
void Servo::detach()
{
timer16_Sequence_t timer;
servos[this->servoIndex].Pin.isActive = false;
timer = SERVO_INDEX_TO_TIMER(servoIndex);
if(isTimerActive(timer) == false) {
finISR(timer);
}
}
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)
{
if (value < 0)
value = 0;
else if (value > 180)
value = 180;
value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX());
}
writeMicroseconds(value);
}
void Servo::writeMicroseconds(int value)
{
// calculate and store the values for the given channel
byte channel = this->servoIndex;
if( (channel < MAX_SERVOS) ) // ensure channel is valid
{
if (value < SERVO_MIN()) // ensure pulse width is valid
value = SERVO_MIN();
else if (value > SERVO_MAX())
value = SERVO_MAX();
value = value - TRIM_DURATION;
value = usToTicks(value); // convert to ticks after compensating for interrupt overhead
servos[channel].ticks = value;
}
}
int Servo::read() // return the value as degrees
{
return map(readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180);
}
int Servo::readMicroseconds()
{
unsigned int pulsewidth;
if (this->servoIndex != INVALID_SERVO)
pulsewidth = ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION;
else
pulsewidth = 0;
return pulsewidth;
}
bool Servo::attached()
{
return servos[this->servoIndex].Pin.isActive;
}
#endif
\ No newline at end of file
/*
Copyright (c) 2018 Arduino LLC. 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 16 bit timers used with Servo library
*
*/
#ifndef __SERVO_TIMERS_H__
#define __SERVO_TIMERS_H__
#define USE_TIMERB1 // interferes with PWM on pin 3
//#define USE_TIMERB2 // interferes with PWM on pin 11
//#define USE_TIMERB0 // interferes with PWM on pin 6
#if !defined(USE_TIMERB1) && !defined(USE_TIMERB2) && !defined(USE_TIMERB0)
# error "No timers allowed for Servo"
/* Please uncomment a timer above and rebuild */
#endif
static volatile TCB_t* _timer =
#if defined(USE_TIMERB0)
&TCB0;
#endif
#if defined(USE_TIMERB1)
&TCB1;
#endif
#if defined(USE_TIMERB2)
&TCB2;
#endif
typedef enum {
timer0,
_Nbr_16timers } timer16_Sequence_t;
#endif /* __SERVO_TIMERS_H__ */
/*
Copyright (c) 2016 Arduino. 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(ARDUINO_ARCH_NRF52)
#include <Arduino.h>
#include <Servo.h>
static servo_t servos[MAX_SERVOS]; // static array of servo structures
uint8_t ServoCount = 0; // the total number of attached servos
uint32_t group_pins[3][NRF_PWM_CHANNEL_COUNT]={{NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED}, {NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED}, {NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED}};
static uint16_t seq_values[3][NRF_PWM_CHANNEL_COUNT]={{0, 0, 0, 0}, {0, 0, 0, 0}, {0, 0, 0, 0}};
Servo::Servo()
{
if (ServoCount < MAX_SERVOS) {
this->servoIndex = ServoCount++; // assign a servo index to this instance
} else {
this->servoIndex = INVALID_SERVO; // too many servos
}
}
uint8_t Servo::attach(int pin)
{
return this->attach(pin, 0, 2500);
}
uint8_t Servo::attach(int pin, int min, int max)
{
int servo_min, servo_max;
if (this->servoIndex < MAX_SERVOS) {
pinMode(pin, OUTPUT); // set servo pin to output
servos[this->servoIndex].Pin.nbr = pin;
if(min < servo_min) min = servo_min;
if (max > servo_max) max = servo_max;
this->min = min;
this->max = max;
servos[this->servoIndex].Pin.isActive = true;
}
return this->servoIndex;
}
void Servo::detach()
{
servos[this->servoIndex].Pin.isActive = false;
}
void Servo::write(int value)
{
if (value < 0)
value = 0;
else if (value > 180)
value = 180;
value = map(value, 0, 180, MIN_PULSE, MAX_PULSE);
writeMicroseconds(value);
}
void Servo::writeMicroseconds(int value)
{
uint8_t channel, instance;
uint8_t pin = servos[this->servoIndex].Pin.nbr;
//instance of pwm module is MSB - look at VWariant.h
instance=(g_APinDescription[pin].ulPWMChannel & 0xF0)/16;
//index of pwm channel is LSB - look at VWariant.h
channel=g_APinDescription[pin].ulPWMChannel & 0x0F;
group_pins[instance][channel]=g_APinDescription[pin].ulPin;
NRF_PWM_Type * PWMInstance = instance == 0 ? NRF_PWM0 : (instance == 1 ? NRF_PWM1 : NRF_PWM2);
//configure pwm instance and enable it
seq_values[instance][channel]= value | 0x8000;
nrf_pwm_sequence_t const seq={
seq_values[instance],
NRF_PWM_VALUES_LENGTH(seq_values),
0,
0
};
nrf_pwm_pins_set(PWMInstance, group_pins[instance]);
nrf_pwm_enable(PWMInstance);
nrf_pwm_configure(PWMInstance, NRF_PWM_CLK_125kHz, NRF_PWM_MODE_UP, 2500); // 20ms - 50Hz
nrf_pwm_decoder_set(PWMInstance, NRF_PWM_LOAD_INDIVIDUAL, NRF_PWM_STEP_AUTO);
nrf_pwm_sequence_set(PWMInstance, 0, &seq);
nrf_pwm_loop_set(PWMInstance, 0UL);
nrf_pwm_task_trigger(PWMInstance, NRF_PWM_TASK_SEQSTART0);
}
int Servo::read() // return the value as degrees
{
return map(readMicroseconds(), MIN_PULSE, MAX_PULSE, 0, 180);
}
int Servo::readMicroseconds()
{
uint8_t channel, instance;
uint8_t pin=servos[this->servoIndex].Pin.nbr;
instance=(g_APinDescription[pin].ulPWMChannel & 0xF0)/16;
channel=g_APinDescription[pin].ulPWMChannel & 0x0F;
// remove the 16th bit we added before
return seq_values[instance][channel] & 0x7FFF;
}
bool Servo::attached()
{
return servos[this->servoIndex].Pin.isActive;
}
#endif // ARDUINO_ARCH_NRF52
\ No newline at end of file
/*
Copyright (c) 2016 Arduino. 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
*/
/*
* NRF52 doesn't use timer, but pwm. This file include definitions to keep
* compatibility with the Servo library standards.
*/
#ifndef __SERVO_TIMERS_H__
#define __SERVO_TIMERS_H__
/**
* NRF52 Only definitions
* ---------------------
*/
#define MIN_PULSE 55
#define MAX_PULSE 284
// define one timer in order to have MAX_SERVOS = 12
typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t;
#endif // __SERVO_TIMERS_H__
\ No newline at end of file
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010, LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
#if defined(ARDUINO_ARCH_STM32F4)
#include "ServoTimers.h"
#include "boards.h"
#include "io.h"
#include "pwm.h"
#include "math.h"
// 20 millisecond period config. For a 1-based prescaler,
//
// (prescaler * overflow / CYC_MSEC) msec = 1 timer cycle = 20 msec
// => prescaler * overflow = 20 * CYC_MSEC
//
// This picks the smallest prescaler that allows an overflow < 2^16.
#define MAX_OVERFLOW ((1 << 16) - 1)
#define CYC_MSEC (1000 * CYCLES_PER_MICROSECOND)
#define TAU_MSEC 20
#define TAU_USEC (TAU_MSEC * 1000)
#define TAU_CYC (TAU_MSEC * CYC_MSEC)
#define SERVO_PRESCALER (TAU_CYC / MAX_OVERFLOW + 1)
#define SERVO_OVERFLOW ((uint16)round((double)TAU_CYC / SERVO_PRESCALER))
// Unit conversions
#define US_TO_COMPARE(us) ((uint16)map((us), 0, TAU_USEC, 0, SERVO_OVERFLOW))
#define COMPARE_TO_US(c) ((uint32)map((c), 0, SERVO_OVERFLOW, 0, TAU_USEC))
#define ANGLE_TO_US(a) ((uint16)(map((a), this->minAngle, this->maxAngle, \
this->minPW, this->maxPW)))
#define US_TO_ANGLE(us) ((int16)(map((us), this->minPW, this->maxPW, \
this->minAngle, this->maxAngle)))
Servo::Servo() {
this->resetFields();
}
bool Servo::attach(uint8 pin, uint16 minPW, uint16 maxPW, int16 minAngle, int16 maxAngle)
{
// SerialUSB.begin(115200);
// SerialUSB.println(MAX_OVERFLOW);
timer_dev *tdev = PIN_MAP[pin].timer_device;
analogWriteResolution(16);
int prescaler = 6;
int overflow = 65400;
int minPW_correction = 300;
int maxPW_correction = 300;
pinMode(pin, OUTPUT);
if (tdev == NULL) {
// don't reset any fields or ASSERT(0), to keep driving any
// previously attach()ed servo.
return false;
}
if ( (tdev == TIMER1) || (tdev == TIMER8) || (tdev == TIMER10) || (tdev == TIMER11))
{
prescaler = 54;
overflow = 65400;
minPW_correction = 40;
maxPW_correction = 50;
}
if ( (tdev == TIMER2) || (tdev == TIMER3) || (tdev == TIMER4) || (tdev == TIMER5) )
{
prescaler = 6;
overflow = 64285;
minPW_correction = 370;
maxPW_correction = 350;
}
if ( (tdev == TIMER6) || (tdev == TIMER7) )
{
prescaler = 6;
overflow = 65400;
minPW_correction = 0;
maxPW_correction = 0;
}
if ( (tdev == TIMER9) || (tdev == TIMER12) || (tdev == TIMER13) || (tdev == TIMER14) )
{
prescaler = 6;
overflow = 65400;
minPW_correction = 30;
maxPW_correction = 0;
}
if (this->attached()) {
this->detach();
}
this->pin = pin;
this->minPW = (minPW + minPW_correction);
this->maxPW = (maxPW + maxPW_correction);
this->minAngle = minAngle;
this->maxAngle = maxAngle;
timer_pause(tdev);
timer_set_prescaler(tdev, prescaler); // prescaler is 1-based
timer_set_reload(tdev, overflow);
timer_generate_update(tdev);
timer_resume(tdev);
return true;
}
bool Servo::detach() {
if (!this->attached()) {
return false;
}
timer_dev *tdev = PIN_MAP[this->pin].timer_device;
uint8 tchan = PIN_MAP[this->pin].timer_channel;
timer_set_mode(tdev, tchan, TIMER_DISABLED);
this->resetFields();
return true;
}
void Servo::write(int degrees) {
degrees = constrain(degrees, this->minAngle, this->maxAngle);
this->writeMicroseconds(ANGLE_TO_US(degrees));
}
int Servo::read() const {
int a = US_TO_ANGLE(this->readMicroseconds());
// map() round-trips in a weird way we mostly correct for here;
// the round-trip is still sometimes off-by-one for write(1) and
// write(179).
return a == this->minAngle || a == this->maxAngle ? a : a + 1;
}
void Servo::writeMicroseconds(uint16 pulseWidth) {
if (!this->attached()) {
ASSERT(0);
return;
}
pulseWidth = constrain(pulseWidth, this->minPW, this->maxPW);
analogWrite(this->pin, US_TO_COMPARE(pulseWidth));
}
uint16 Servo::readMicroseconds() const {
if (!this->attached()) {
ASSERT(0);
return 0;
}
stm32_pin_info pin_info = PIN_MAP[this->pin];
uint16 compare = timer_get_compare(pin_info.timer_device,
pin_info.timer_channel);
return COMPARE_TO_US(compare);
}
void Servo::resetFields(void) {
this->pin = NOT_ATTACHED;
this->minAngle = MIN_ANGLE;
this->maxAngle = MAX_ANGLE;
this->minPW = MIN_PULSE_WIDTH;
this->maxPW = MAX_PULSE_WIDTH;
}
#endif
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010, LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/*
* Arduino srl - www.arduino.org
* 2017 Feb 23: Edited by Francesco Alessi (alfran) - francesco@arduino.org