1
0
mirror of https://github.com/arduino/Arduino.git synced 2024-11-29 10:24:12 +01:00

Servo library to format 1.5 rev.2

This commit is contained in:
Cristian Maglie 2014-01-02 00:20:31 +01:00
parent 03a7cf3212
commit 4b7302692c
6 changed files with 626 additions and 620 deletions

View File

@ -1,10 +1,8 @@
name=Servo name=Servo
author= version=1.0
email= author=Michael Margolis, Arduino
maintainer=Arduino <info@arduino.cc>
sentence=Controls a lot of Servos. sentence=Controls a lot of Servos.
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 /> 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 />
url=http://arduino.cc/en/Reference/Servo url=http://arduino.cc/en/Reference/Servo
architectures=avr,sam architectures=avr,sam
version=1.0
dependencies=
core-dependencies=arduino (>=1.5.0)

View File

@ -59,7 +59,13 @@
*/ */
// Architecture specific include // Architecture specific include
#include <ServoTimers.h> #if defined(ARDUINO_ARCH_AVR)
#include "avr/ServoTimers.h"
#elif defined(ARDUINO_ARCH_SAM)
#include "sam/ServoTimers.h"
#else
#error "This library only supports boards with an AVR or SAM processor."
#endif
#define Servo_VERSION 2 // software version of this library #define Servo_VERSION 2 // software version of this library

View File

@ -1,313 +1,317 @@
/* /*
Servo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2 Servo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
Copyright (c) 2009 Michael Margolis. All right reserved. Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version. 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, This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details. Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/ */
#include <avr/interrupt.h> #if defined(ARDUINO_ARCH_AVR)
#include <Arduino.h>
#include <avr/interrupt.h>
#include "Servo.h" #include <Arduino.h>
#define usToTicks(_us) (( clockCyclesPerMicrosecond()* _us) / 8) // converts microseconds to tick (assumes prescale of 8) // 12 Aug 2009 #include "Servo.h"
#define ticksToUs(_ticks) (( (unsigned)_ticks * 8)/ clockCyclesPerMicrosecond() ) // converts from ticks back to microseconds
#define usToTicks(_us) (( clockCyclesPerMicrosecond()* _us) / 8) // converts microseconds to tick (assumes prescale of 8) // 12 Aug 2009
#define ticksToUs(_ticks) (( (unsigned)_ticks * 8)/ clockCyclesPerMicrosecond() ) // converts from ticks back to microseconds
#define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays // 12 August 2009
//#define NBR_TIMERS (MAX_SERVOS / SERVOS_PER_TIMER) #define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays // 12 August 2009
static servo_t servos[MAX_SERVOS]; // static array of servo structures //#define NBR_TIMERS (MAX_SERVOS / SERVOS_PER_TIMER)
static volatile int8_t Channel[_Nbr_16timers ]; // counter for the servo being pulsed for each timer (or -1 if refresh interval)
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 Channel[_Nbr_16timers ]; // counter for the servo being pulsed for each timer (or -1 if refresh interval)
uint8_t ServoCount = 0; // the total number of attached servos
// 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 // convenience macros
#define SERVO_INDEX(_timer,_channel) ((_timer*SERVOS_PER_TIMER) + _channel) // macro to access servo index by timer and channel #define SERVO_INDEX_TO_TIMER(_servo_nbr) ((timer16_Sequence_t)(_servo_nbr / SERVOS_PER_TIMER)) // returns the timer controlling this servo
#define SERVO(_timer,_channel) (servos[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel #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_MIN() (MIN_PULSE_WIDTH - this->min * 4) // minimum value in uS for this servo #define SERVO(_timer,_channel) (servos[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel
#define SERVO_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo
#define SERVO_MIN() (MIN_PULSE_WIDTH - this->min * 4) // minimum value in uS for this servo
/************ static functions common to all instances ***********************/ #define SERVO_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo
static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t *TCNTn, volatile uint16_t* OCRnA) /************ static functions common to all instances ***********************/
{
if( Channel[timer] < 0 ) static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t *TCNTn, volatile uint16_t* OCRnA)
*TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer {
else{ if( Channel[timer] < 0 )
if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive == true ) *TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,LOW); // pulse this channel low if activated else{
} if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive == true )
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,LOW); // pulse this channel low if activated
Channel[timer]++; // increment to the next channel }
if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
*OCRnA = *TCNTn + SERVO(timer,Channel[timer]).ticks; Channel[timer]++; // increment to the next channel
if(SERVO(timer,Channel[timer]).Pin.isActive == true) // check if activated if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high *OCRnA = *TCNTn + SERVO(timer,Channel[timer]).ticks;
} if(SERVO(timer,Channel[timer]).Pin.isActive == true) // check if activated
else { digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high
// finished all channels so wait for the refresh period to expire before starting over }
if( ((unsigned)*TCNTn) + 4 < usToTicks(REFRESH_INTERVAL) ) // allow a few ticks to ensure the next OCR1A not missed else {
*OCRnA = (unsigned int)usToTicks(REFRESH_INTERVAL); // finished all channels so wait for the refresh period to expire before starting over
else if( ((unsigned)*TCNTn) + 4 < usToTicks(REFRESH_INTERVAL) ) // allow a few ticks to ensure the next OCR1A not missed
*OCRnA = *TCNTn + 4; // at least REFRESH_INTERVAL has elapsed *OCRnA = (unsigned int)usToTicks(REFRESH_INTERVAL);
Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel else
} *OCRnA = *TCNTn + 4; // at least REFRESH_INTERVAL has elapsed
} Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
}
#ifndef WIRING // Wiring pre-defines signal handlers so don't define any if compiling for the Wiring platform }
// Interrupt handlers for Arduino
#if defined(_useTimer1) #ifndef WIRING // Wiring pre-defines signal handlers so don't define any if compiling for the Wiring platform
SIGNAL (TIMER1_COMPA_vect) // Interrupt handlers for Arduino
{ #if defined(_useTimer1)
handle_interrupts(_timer1, &TCNT1, &OCR1A); SIGNAL (TIMER1_COMPA_vect)
} {
#endif handle_interrupts(_timer1, &TCNT1, &OCR1A);
}
#if defined(_useTimer3) #endif
SIGNAL (TIMER3_COMPA_vect)
{ #if defined(_useTimer3)
handle_interrupts(_timer3, &TCNT3, &OCR3A); SIGNAL (TIMER3_COMPA_vect)
} {
#endif handle_interrupts(_timer3, &TCNT3, &OCR3A);
}
#if defined(_useTimer4) #endif
SIGNAL (TIMER4_COMPA_vect)
{ #if defined(_useTimer4)
handle_interrupts(_timer4, &TCNT4, &OCR4A); SIGNAL (TIMER4_COMPA_vect)
} {
#endif handle_interrupts(_timer4, &TCNT4, &OCR4A);
}
#if defined(_useTimer5) #endif
SIGNAL (TIMER5_COMPA_vect)
{ #if defined(_useTimer5)
handle_interrupts(_timer5, &TCNT5, &OCR5A); SIGNAL (TIMER5_COMPA_vect)
} {
#endif handle_interrupts(_timer5, &TCNT5, &OCR5A);
}
#elif defined WIRING #endif
// Interrupt handlers for Wiring
#if defined(_useTimer1) #elif defined WIRING
void Timer1Service() // Interrupt handlers for Wiring
{ #if defined(_useTimer1)
handle_interrupts(_timer1, &TCNT1, &OCR1A); void Timer1Service()
} {
#endif handle_interrupts(_timer1, &TCNT1, &OCR1A);
#if defined(_useTimer3) }
void Timer3Service() #endif
{ #if defined(_useTimer3)
handle_interrupts(_timer3, &TCNT3, &OCR3A); void Timer3Service()
} {
#endif handle_interrupts(_timer3, &TCNT3, &OCR3A);
#endif }
#endif
#endif
static void initISR(timer16_Sequence_t timer)
{
#if defined (_useTimer1) static void initISR(timer16_Sequence_t timer)
if(timer == _timer1) { {
TCCR1A = 0; // normal counting mode #if defined (_useTimer1)
TCCR1B = _BV(CS11); // set prescaler of 8 if(timer == _timer1) {
TCNT1 = 0; // clear the timer count TCCR1A = 0; // normal counting mode
#if defined(__AVR_ATmega8__)|| defined(__AVR_ATmega128__) TCCR1B = _BV(CS11); // set prescaler of 8
TIFR |= _BV(OCF1A); // clear any pending interrupts; TCNT1 = 0; // clear the timer count
TIMSK |= _BV(OCIE1A) ; // enable the output compare interrupt #if defined(__AVR_ATmega8__)|| defined(__AVR_ATmega128__)
#else TIFR |= _BV(OCF1A); // clear any pending interrupts;
// here if not ATmega8 or ATmega128 TIMSK |= _BV(OCIE1A) ; // enable the output compare interrupt
TIFR1 |= _BV(OCF1A); // clear any pending interrupts; #else
TIMSK1 |= _BV(OCIE1A) ; // enable the output compare interrupt // here if not ATmega8 or ATmega128
#endif TIFR1 |= _BV(OCF1A); // clear any pending interrupts;
#if defined(WIRING) TIMSK1 |= _BV(OCIE1A) ; // enable the output compare interrupt
timerAttach(TIMER1OUTCOMPAREA_INT, Timer1Service); #endif
#endif #if defined(WIRING)
} timerAttach(TIMER1OUTCOMPAREA_INT, Timer1Service);
#endif #endif
}
#if defined (_useTimer3) #endif
if(timer == _timer3) {
TCCR3A = 0; // normal counting mode #if defined (_useTimer3)
TCCR3B = _BV(CS31); // set prescaler of 8 if(timer == _timer3) {
TCNT3 = 0; // clear the timer count TCCR3A = 0; // normal counting mode
#if defined(__AVR_ATmega128__) TCCR3B = _BV(CS31); // set prescaler of 8
TIFR |= _BV(OCF3A); // clear any pending interrupts; TCNT3 = 0; // clear the timer count
ETIMSK |= _BV(OCIE3A); // enable the output compare interrupt #if defined(__AVR_ATmega128__)
#else TIFR |= _BV(OCF3A); // clear any pending interrupts;
TIFR3 = _BV(OCF3A); // clear any pending interrupts; ETIMSK |= _BV(OCIE3A); // enable the output compare interrupt
TIMSK3 = _BV(OCIE3A) ; // enable the output compare interrupt #else
#endif TIFR3 = _BV(OCF3A); // clear any pending interrupts;
#if defined(WIRING) TIMSK3 = _BV(OCIE3A) ; // enable the output compare interrupt
timerAttach(TIMER3OUTCOMPAREA_INT, Timer3Service); // for Wiring platform only #endif
#endif #if defined(WIRING)
} timerAttach(TIMER3OUTCOMPAREA_INT, Timer3Service); // for Wiring platform only
#endif #endif
}
#if defined (_useTimer4) #endif
if(timer == _timer4) {
TCCR4A = 0; // normal counting mode #if defined (_useTimer4)
TCCR4B = _BV(CS41); // set prescaler of 8 if(timer == _timer4) {
TCNT4 = 0; // clear the timer count TCCR4A = 0; // normal counting mode
TIFR4 = _BV(OCF4A); // clear any pending interrupts; TCCR4B = _BV(CS41); // set prescaler of 8
TIMSK4 = _BV(OCIE4A) ; // enable the output compare interrupt TCNT4 = 0; // clear the timer count
} TIFR4 = _BV(OCF4A); // clear any pending interrupts;
#endif TIMSK4 = _BV(OCIE4A) ; // enable the output compare interrupt
}
#if defined (_useTimer5) #endif
if(timer == _timer5) {
TCCR5A = 0; // normal counting mode #if defined (_useTimer5)
TCCR5B = _BV(CS51); // set prescaler of 8 if(timer == _timer5) {
TCNT5 = 0; // clear the timer count TCCR5A = 0; // normal counting mode
TIFR5 = _BV(OCF5A); // clear any pending interrupts; TCCR5B = _BV(CS51); // set prescaler of 8
TIMSK5 = _BV(OCIE5A) ; // enable the output compare interrupt TCNT5 = 0; // clear the timer count
} TIFR5 = _BV(OCF5A); // clear any pending interrupts;
#endif TIMSK5 = _BV(OCIE5A) ; // enable the output compare interrupt
} }
#endif
static void finISR(timer16_Sequence_t timer) }
{
//disable use of the given timer static void finISR(timer16_Sequence_t timer)
#if defined WIRING // Wiring {
if(timer == _timer1) { //disable use of the given timer
#if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__) #if defined WIRING // Wiring
TIMSK1 &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt if(timer == _timer1) {
#else #if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
TIMSK &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt TIMSK1 &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt
#endif #else
timerDetach(TIMER1OUTCOMPAREA_INT); TIMSK &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt
} #endif
else if(timer == _timer3) { timerDetach(TIMER1OUTCOMPAREA_INT);
#if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__) }
TIMSK3 &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt else if(timer == _timer3) {
#else #if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
ETIMSK &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt TIMSK3 &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt
#endif #else
timerDetach(TIMER3OUTCOMPAREA_INT); ETIMSK &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt
} #endif
#else timerDetach(TIMER3OUTCOMPAREA_INT);
//For arduino - in future: call here to a currently undefined function to reset the timer }
#endif #else
} //For arduino - in future: call here to a currently undefined function to reset the timer
#endif
static boolean isTimerActive(timer16_Sequence_t timer) }
{
// returns true if any servo is active on this timer static boolean isTimerActive(timer16_Sequence_t timer)
for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) { {
if(SERVO(timer,channel).Pin.isActive == true) // returns true if any servo is active on this timer
return true; for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) {
} if(SERVO(timer,channel).Pin.isActive == true)
return false; return true;
} }
return false;
}
/****************** end of static functions ******************************/
Servo::Servo() /****************** end of static functions ******************************/
{
if( ServoCount < MAX_SERVOS) { Servo::Servo()
this->servoIndex = ServoCount++; // assign a servo index to this instance {
servos[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009 if( ServoCount < MAX_SERVOS) {
} this->servoIndex = ServoCount++; // assign a servo index to this instance
else servos[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009
this->servoIndex = INVALID_SERVO ; // too many servos }
} 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)
} {
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
uint8_t Servo::attach(int pin, int min, int max) }
{
if(this->servoIndex < MAX_SERVOS ) { uint8_t Servo::attach(int pin, int min, int max)
pinMode( pin, OUTPUT) ; // set servo pin to output {
servos[this->servoIndex].Pin.nbr = pin; if(this->servoIndex < MAX_SERVOS ) {
// todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128 pinMode( pin, OUTPUT) ; // set servo pin to output
this->min = (MIN_PULSE_WIDTH - min)/4; //resolution of min/max is 4 uS servos[this->servoIndex].Pin.nbr = pin;
this->max = (MAX_PULSE_WIDTH - max)/4; // todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128
// initialize the timer if it has not already been initialized this->min = (MIN_PULSE_WIDTH - min)/4; //resolution of min/max is 4 uS
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex); this->max = (MAX_PULSE_WIDTH - max)/4;
if(isTimerActive(timer) == false) // initialize the timer if it has not already been initialized
initISR(timer); timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive if(isTimerActive(timer) == false)
} initISR(timer);
return this->servoIndex ; servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
} }
return this->servoIndex ;
void Servo::detach() }
{
servos[this->servoIndex].Pin.isActive = false; void Servo::detach()
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex); {
if(isTimerActive(timer) == false) { servos[this->servoIndex].Pin.isActive = false;
finISR(timer); timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
} if(isTimerActive(timer) == false) {
} finISR(timer);
}
void Servo::write(int value) }
{
if(value < MIN_PULSE_WIDTH) void Servo::write(int value)
{ // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds) {
if(value < 0) value = 0; if(value < MIN_PULSE_WIDTH)
if(value > 180) value = 180; { // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX()); if(value < 0) value = 0;
} if(value > 180) value = 180;
this->writeMicroseconds(value); value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX());
} }
this->writeMicroseconds(value);
void Servo::writeMicroseconds(int value) }
{
// calculate and store the values for the given channel void Servo::writeMicroseconds(int value)
byte channel = this->servoIndex; {
if( (channel < MAX_SERVOS) ) // ensure channel is valid // calculate and store the values for the given channel
{ byte channel = this->servoIndex;
if( value < SERVO_MIN() ) // ensure pulse width is valid if( (channel < MAX_SERVOS) ) // ensure channel is valid
value = SERVO_MIN(); {
else if( value > SERVO_MAX() ) if( value < SERVO_MIN() ) // ensure pulse width is valid
value = SERVO_MAX(); value = SERVO_MIN();
else if( value > SERVO_MAX() )
value = value - TRIM_DURATION; value = SERVO_MAX();
value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009
value = value - TRIM_DURATION;
uint8_t oldSREG = SREG; value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009
cli();
servos[channel].ticks = value; uint8_t oldSREG = SREG;
SREG = oldSREG; cli();
} servos[channel].ticks = value;
} SREG = oldSREG;
}
int Servo::read() // return the value as degrees }
{
return map( this->readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180); int Servo::read() // return the value as degrees
} {
return map( this->readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180);
int Servo::readMicroseconds() }
{
unsigned int pulsewidth; int Servo::readMicroseconds()
if( this->servoIndex != INVALID_SERVO ) {
pulsewidth = ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION ; // 12 aug 2009 unsigned int pulsewidth;
else if( this->servoIndex != INVALID_SERVO )
pulsewidth = 0; pulsewidth = ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION ; // 12 aug 2009
else
return pulsewidth; pulsewidth = 0;
}
return pulsewidth;
bool Servo::attached() }
{
return servos[this->servoIndex].Pin.isActive ; bool Servo::attached()
} {
return servos[this->servoIndex].Pin.isActive ;
}
#endif // ARDUINO_ARCH_AVR

View File

@ -17,8 +17,8 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/ */
/* /*
* Defines for 16 bit timers used with Servo library * Defines for 16 bit timers used with Servo library
* *
* If _useTimerX is defined then TimerX is a 16 bit timer on the current board * If _useTimerX is defined then TimerX is a 16 bit timer on the current board
* timer16_Sequence_t enumerates the sequence that the timers should be allocated * timer16_Sequence_t enumerates the sequence that the timers should be allocated
@ -33,27 +33,27 @@
// Say which 16 bit timers can be used and in what order // Say which 16 bit timers can be used and in what order
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#define _useTimer5 #define _useTimer5
#define _useTimer1 #define _useTimer1
#define _useTimer3 #define _useTimer3
#define _useTimer4 #define _useTimer4
typedef enum { _timer5, _timer1, _timer3, _timer4, _Nbr_16timers } timer16_Sequence_t ; typedef enum { _timer5, _timer1, _timer3, _timer4, _Nbr_16timers } timer16_Sequence_t;
#elif defined(__AVR_ATmega32U4__) #elif defined(__AVR_ATmega32U4__)
#define _useTimer1 #define _useTimer1
typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t ; typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t;
#elif defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__) #elif defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__)
#define _useTimer3 #define _useTimer3
#define _useTimer1 #define _useTimer1
typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t ; 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_ATmega2561__)
#define _useTimer3 #define _useTimer3
#define _useTimer1 #define _useTimer1
typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t ; typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t;
#else // everything else #else // everything else
#define _useTimer1 #define _useTimer1
typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t ; typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t;
#endif #endif

View File

@ -1,284 +1,283 @@
/* /*
Servo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers - Version 2 Copyright (c) 2013 Arduino LLC. All right reserved.
Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or
This library is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public
modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either
License as published by the Free Software Foundation; either version 2.1 of the License, or (at your option) any later version.
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,
This library is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of
but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
You should have received a copy of the GNU Lesser General Public License along with this library; if not, write to the Free Software
License along with this library; if not, write to the Free Software Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA */
*/
#if defined(ARDUINO_ARCH_SAM)
#include <Arduino.h>
#include <Servo.h> #include <Arduino.h>
#include <Servo.h>
#define usToTicks(_us) (( clockCyclesPerMicrosecond() * _us) / 32) // converts microseconds to tick
#define ticksToUs(_ticks) (( (unsigned)_ticks * 32)/ clockCyclesPerMicrosecond() ) // converts from ticks back to microseconds #define usToTicks(_us) (( clockCyclesPerMicrosecond() * _us) / 32) // converts microseconds to tick
#define ticksToUs(_ticks) (( (unsigned)_ticks * 32)/ clockCyclesPerMicrosecond() ) // converts from ticks back to microseconds
#define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays #define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays
static servo_t servos[MAX_SERVOS]; // static array of servo structures static servo_t servos[MAX_SERVOS]; // static array of servo structures
uint8_t ServoCount = 0; // the total number of attached servos uint8_t ServoCount = 0; // the total number of attached servos
static volatile int8_t Channel[_Nbr_16timers ]; // counter for the servo being pulsed for each timer (or -1 if refresh interval) static volatile int8_t Channel[_Nbr_16timers ]; // counter for the servo being pulsed for each timer (or -1 if refresh interval)
// convenience macros // 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_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_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_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(_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_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 #define SERVO_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo
/************ static functions common to all instances ***********************/ /************ static functions common to all instances ***********************/
//------------------------------------------------------------------------------
//timer16_Sequence_t timer; /// Interrupt handler for the TC0 channel 1.
//------------------------------------------------------------------------------
//------------------------------------------------------------------------------ void Servo_Handler(timer16_Sequence_t timer, Tc *pTc, uint8_t channel);
/// Interrupt handler for the TC0 channel 1. #if defined (_useTimer1)
//------------------------------------------------------------------------------ void HANDLER_FOR_TIMER1(void) {
void Servo_Handler(timer16_Sequence_t timer, Tc *pTc, uint8_t channel); Servo_Handler(_timer1, TC_FOR_TIMER1, CHANNEL_FOR_TIMER1);
#if defined (_useTimer1) }
void HANDLER_FOR_TIMER1(void) { #endif
Servo_Handler(_timer1, TC_FOR_TIMER1, CHANNEL_FOR_TIMER1); #if defined (_useTimer2)
} void HANDLER_FOR_TIMER2(void) {
#endif Servo_Handler(_timer2, TC_FOR_TIMER2, CHANNEL_FOR_TIMER2);
#if defined (_useTimer2) }
void HANDLER_FOR_TIMER2(void) { #endif
Servo_Handler(_timer2, TC_FOR_TIMER2, CHANNEL_FOR_TIMER2); #if defined (_useTimer3)
} void HANDLER_FOR_TIMER3(void) {
#endif Servo_Handler(_timer3, TC_FOR_TIMER3, CHANNEL_FOR_TIMER3);
#if defined (_useTimer3) }
void HANDLER_FOR_TIMER3(void) { #endif
Servo_Handler(_timer3, TC_FOR_TIMER3, CHANNEL_FOR_TIMER3); #if defined (_useTimer4)
} void HANDLER_FOR_TIMER4(void) {
#endif Servo_Handler(_timer4, TC_FOR_TIMER4, CHANNEL_FOR_TIMER4);
#if defined (_useTimer4) }
void HANDLER_FOR_TIMER4(void) { #endif
Servo_Handler(_timer4, TC_FOR_TIMER4, CHANNEL_FOR_TIMER4); #if defined (_useTimer5)
} void HANDLER_FOR_TIMER5(void) {
#endif Servo_Handler(_timer5, TC_FOR_TIMER5, CHANNEL_FOR_TIMER5);
#if defined (_useTimer5) }
void HANDLER_FOR_TIMER5(void) { #endif
Servo_Handler(_timer5, TC_FOR_TIMER5, CHANNEL_FOR_TIMER5);
} void Servo_Handler(timer16_Sequence_t timer, Tc *tc, uint8_t channel)
#endif {
// clear interrupt
void Servo_Handler(timer16_Sequence_t timer, Tc *tc, uint8_t channel) tc->TC_CHANNEL[channel].TC_SR;
{ if (Channel[timer] < 0) {
// clear interrupt tc->TC_CHANNEL[channel].TC_CCR |= TC_CCR_SWTRG; // channel set to -1 indicated that refresh interval completed so reset the timer
tc->TC_CHANNEL[channel].TC_SR; } else {
if (Channel[timer] < 0) { if (SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive == true) {
tc->TC_CHANNEL[channel].TC_CCR |= TC_CCR_SWTRG; // channel set to -1 indicated that refresh interval completed so reset the timer digitalWrite(SERVO(timer,Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
} else { }
if (SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive == true) { }
digitalWrite(SERVO(timer,Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
} Channel[timer]++; // increment to the next channel
} if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + SERVO(timer,Channel[timer]).ticks;
Channel[timer]++; // increment to the next channel if(SERVO(timer,Channel[timer]).Pin.isActive == true) { // check if activated
if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) { digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high
tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + SERVO(timer,Channel[timer]).ticks; }
if(SERVO(timer,Channel[timer]).Pin.isActive == true) { // check if activated }
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high else {
} // finished all channels so wait for the refresh period to expire before starting over
} if( (tc->TC_CHANNEL[channel].TC_CV) + 4 < usToTicks(REFRESH_INTERVAL) ) { // allow a few ticks to ensure the next OCR1A not missed
else { tc->TC_CHANNEL[channel].TC_RA = (unsigned int)usToTicks(REFRESH_INTERVAL);
// finished all channels so wait for the refresh period to expire before starting over }
if( (tc->TC_CHANNEL[channel].TC_CV) + 4 < usToTicks(REFRESH_INTERVAL) ) { // allow a few ticks to ensure the next OCR1A not missed else {
tc->TC_CHANNEL[channel].TC_RA = (unsigned int)usToTicks(REFRESH_INTERVAL); tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + 4; // at least REFRESH_INTERVAL has elapsed
} }
else { Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + 4; // at least REFRESH_INTERVAL has elapsed }
} }
Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
} static void _initISR(Tc *tc, uint32_t channel, uint32_t id, IRQn_Type irqn)
} {
pmc_enable_periph_clk(id);
static void _initISR(Tc *tc, uint32_t channel, uint32_t id, IRQn_Type irqn) TC_Configure(tc, channel,
{ TC_CMR_TCCLKS_TIMER_CLOCK3 | // MCK/32
pmc_enable_periph_clk(id); TC_CMR_WAVE | // Waveform mode
TC_Configure(tc, channel, TC_CMR_WAVSEL_UP_RC ); // Counter running up and reset when equals to RC
TC_CMR_TCCLKS_TIMER_CLOCK3 | // MCK/32
TC_CMR_WAVE | // Waveform mode /* 84MHz, MCK/32, for 1.5ms: 3937 */
TC_CMR_WAVSEL_UP_RC ); // Counter running up and reset when equals to RC TC_SetRA(tc, channel, 2625); // 1ms
/* 84MHz, MCK/32, for 1.5ms: 3937 */ /* Configure and enable interrupt */
TC_SetRA(tc, channel, 2625); // 1ms NVIC_EnableIRQ(irqn);
// TC_IER_CPAS: RA Compare
/* Configure and enable interrupt */ tc->TC_CHANNEL[channel].TC_IER = TC_IER_CPAS;
NVIC_EnableIRQ(irqn);
// TC_IER_CPAS: RA Compare // Enables the timer clock and performs a software reset to start the counting
tc->TC_CHANNEL[channel].TC_IER = TC_IER_CPAS; TC_Start(tc, channel);
}
// Enables the timer clock and performs a software reset to start the counting
TC_Start(tc, channel); static void initISR(timer16_Sequence_t timer)
} {
#if defined (_useTimer1)
static void initISR(timer16_Sequence_t timer) if (timer == _timer1)
{ _initISR(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1, ID_TC_FOR_TIMER1, IRQn_FOR_TIMER1);
#if defined (_useTimer1) #endif
if (timer == _timer1) #if defined (_useTimer2)
_initISR(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1, ID_TC_FOR_TIMER1, IRQn_FOR_TIMER1); if (timer == _timer2)
#endif _initISR(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2, ID_TC_FOR_TIMER2, IRQn_FOR_TIMER2);
#if defined (_useTimer2) #endif
if (timer == _timer2) #if defined (_useTimer3)
_initISR(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2, ID_TC_FOR_TIMER2, IRQn_FOR_TIMER2); if (timer == _timer3)
#endif _initISR(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3, ID_TC_FOR_TIMER3, IRQn_FOR_TIMER3);
#if defined (_useTimer3) #endif
if (timer == _timer3) #if defined (_useTimer4)
_initISR(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3, ID_TC_FOR_TIMER3, IRQn_FOR_TIMER3); if (timer == _timer4)
#endif _initISR(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4, ID_TC_FOR_TIMER4, IRQn_FOR_TIMER4);
#if defined (_useTimer4) #endif
if (timer == _timer4) #if defined (_useTimer5)
_initISR(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4, ID_TC_FOR_TIMER4, IRQn_FOR_TIMER4); if (timer == _timer5)
#endif _initISR(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5, ID_TC_FOR_TIMER5, IRQn_FOR_TIMER5);
#if defined (_useTimer5) #endif
if (timer == _timer5) }
_initISR(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5, ID_TC_FOR_TIMER5, IRQn_FOR_TIMER5);
#endif static void finISR(timer16_Sequence_t timer)
} {
#if defined (_useTimer1)
static void finISR(timer16_Sequence_t timer) TC_Stop(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1);
{ #endif
#if defined (_useTimer1) #if defined (_useTimer2)
TC_Stop(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1); TC_Stop(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2);
#endif #endif
#if defined (_useTimer2) #if defined (_useTimer3)
TC_Stop(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2); TC_Stop(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3);
#endif #endif
#if defined (_useTimer3) #if defined (_useTimer4)
TC_Stop(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3); TC_Stop(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4);
#endif #endif
#if defined (_useTimer4) #if defined (_useTimer5)
TC_Stop(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4); TC_Stop(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5);
#endif #endif
#if defined (_useTimer5) }
TC_Stop(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5);
#endif
} static boolean isTimerActive(timer16_Sequence_t timer)
{
// returns true if any servo is active on this timer
static boolean isTimerActive(timer16_Sequence_t timer) for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) {
{ if(SERVO(timer,channel).Pin.isActive == true)
// returns true if any servo is active on this timer return true;
for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) { }
if(SERVO(timer,channel).Pin.isActive == true) return false;
return true; }
}
return false; /****************** end of static functions ******************************/
}
Servo::Servo()
/****************** end of static functions ******************************/ {
if (ServoCount < MAX_SERVOS) {
Servo::Servo() this->servoIndex = ServoCount++; // assign a servo index to this instance
{ servos[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values
if (ServoCount < MAX_SERVOS) { } else {
this->servoIndex = ServoCount++; // assign a servo index to this instance this->servoIndex = INVALID_SERVO; // too many servos
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) }
{
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH); uint8_t Servo::attach(int pin, int min, int max)
} {
timer16_Sequence_t timer;
uint8_t Servo::attach(int pin, int min, int max)
{ if (this->servoIndex < MAX_SERVOS) {
timer16_Sequence_t timer; pinMode(pin, OUTPUT); // set servo pin to output
servos[this->servoIndex].Pin.nbr = pin;
if (this->servoIndex < MAX_SERVOS) { // todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128
pinMode(pin, OUTPUT); // set servo pin to output this->min = (MIN_PULSE_WIDTH - min)/4; //resolution of min/max is 4 uS
servos[this->servoIndex].Pin.nbr = pin; this->max = (MAX_PULSE_WIDTH - max)/4;
// todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128 // initialize the timer if it has not already been initialized
this->min = (MIN_PULSE_WIDTH - min)/4; //resolution of min/max is 4 uS timer = SERVO_INDEX_TO_TIMER(servoIndex);
this->max = (MAX_PULSE_WIDTH - max)/4; if (isTimerActive(timer) == false) {
// initialize the timer if it has not already been initialized initISR(timer);
timer = SERVO_INDEX_TO_TIMER(servoIndex); }
if (isTimerActive(timer) == false) { servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
initISR(timer); }
} return this->servoIndex;
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;
void Servo::detach()
{ servos[this->servoIndex].Pin.isActive = false;
timer16_Sequence_t timer; timer = SERVO_INDEX_TO_TIMER(servoIndex);
if(isTimerActive(timer) == false) {
servos[this->servoIndex].Pin.isActive = false; finISR(timer);
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)
void Servo::write(int value) if (value < MIN_PULSE_WIDTH)
{ {
// treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds) if (value < 0)
if (value < MIN_PULSE_WIDTH) value = 0;
{ else if (value > 180)
if (value < 0) value = 180;
value = 0;
else if (value > 180) value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX());
value = 180; }
writeMicroseconds(value);
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
void Servo::writeMicroseconds(int value) byte channel = this->servoIndex;
{ if( (channel < MAX_SERVOS) ) // ensure channel is valid
// calculate and store the values for the given channel {
byte channel = this->servoIndex; if (value < SERVO_MIN()) // ensure pulse width is valid
if( (channel < MAX_SERVOS) ) // ensure channel is valid value = SERVO_MIN();
{ else if (value > SERVO_MAX())
if (value < SERVO_MIN()) // ensure pulse width is valid value = SERVO_MAX();
value = SERVO_MIN();
else if (value > SERVO_MAX()) value = value - TRIM_DURATION;
value = SERVO_MAX(); value = usToTicks(value); // convert to ticks after compensating for interrupt overhead
servos[channel].ticks = value;
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::read() // return the value as degrees }
{
return map(readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180); int Servo::readMicroseconds()
} {
unsigned int pulsewidth;
int Servo::readMicroseconds() if (this->servoIndex != INVALID_SERVO)
{ pulsewidth = ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION;
unsigned int pulsewidth; else
if (this->servoIndex != INVALID_SERVO) pulsewidth = 0;
pulsewidth = ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION;
else return pulsewidth;
pulsewidth = 0; }
return pulsewidth; bool Servo::attached()
} {
return servos[this->servoIndex].Pin.isActive;
bool Servo::attached() }
{
return servos[this->servoIndex].Pin.isActive; #endif // ARDUINO_ARCH_SAM
}

View File

@ -1,6 +1,5 @@
/* /*
Servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2 Copyright (c) 2013 Arduino LLC. All right reserved.
Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public modify it under the terms of the GNU Lesser General Public
@ -9,16 +8,16 @@
This library is distributed in the hope that it will be useful, This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details. Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/ */
/* /*
* Defines for 16 bit timers used with Servo library * Defines for 16 bit timers used with Servo library
* *
* If _useTimerX is defined then TimerX is a 16 bit timer on the current board * If _useTimerX is defined then TimerX is a 16 bit timer on the current board
* timer16_Sequence_t enumerates the sequence that the timers should be allocated * timer16_Sequence_t enumerates the sequence that the timers should be allocated