Merge pull request #1408 from thinkyhead/cleanup_servo

Formatting cleanup of quiet sources
This commit is contained in:
Scott Lahteine 2015-01-27 22:09:04 -08:00
commit 7378a7fef4
2 changed files with 185 additions and 225 deletions

View File

@ -44,6 +44,7 @@
#include "Configuration.h" #include "Configuration.h"
#ifdef NUM_SERVOS #ifdef NUM_SERVOS
#include <avr/interrupt.h> #include <avr/interrupt.h>
#include <Arduino.h> #include <Arduino.h>
@ -52,7 +53,6 @@
#define usToTicks(_us) (( clockCyclesPerMicrosecond()* _us) / 8) // converts microseconds to tick (assumes prescale of 8) // 12 Aug 2009 #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 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 TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays // 12 August 2009
//#define NBR_TIMERS (MAX_SERVOS / SERVOS_PER_TIMER) //#define NBR_TIMERS (MAX_SERVOS / SERVOS_PER_TIMER)
@ -74,19 +74,18 @@ uint8_t ServoCount = 0; // the total number
/************ static functions common to all instances ***********************/ /************ static functions common to all instances ***********************/
static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t *TCNTn, volatile uint16_t* OCRnA) static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t *TCNTn, volatile uint16_t* OCRnA) {
{
if (Channel[timer] < 0) if (Channel[timer] < 0)
*TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer *TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer
else { else {
if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive == true ) if (SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive)
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,LOW); // pulse this channel low if activated digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,LOW); // pulse this channel low if activated
} }
Channel[timer]++; // increment to the next channel Channel[timer]++; // increment to the next channel
if (SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) { if (SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
*OCRnA = *TCNTn + SERVO(timer,Channel[timer]).ticks; *OCRnA = *TCNTn + SERVO(timer,Channel[timer]).ticks;
if(SERVO(timer,Channel[timer]).Pin.isActive == true) // check if activated if (SERVO(timer,Channel[timer]).Pin.isActive) // check if activated
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high
} }
else { else {
@ -100,54 +99,38 @@ static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t
} }
#ifndef WIRING // Wiring pre-defines signal handlers so don't define any if compiling for the Wiring platform #ifndef WIRING // Wiring pre-defines signal handlers so don't define any if compiling for the Wiring platform
// Interrupt handlers for Arduino // Interrupt handlers for Arduino
#if defined(_useTimer1) #if defined(_useTimer1)
SIGNAL (TIMER1_COMPA_vect) SIGNAL (TIMER1_COMPA_vect) { handle_interrupts(_timer1, &TCNT1, &OCR1A); }
{
handle_interrupts(_timer1, &TCNT1, &OCR1A);
}
#endif #endif
#if defined(_useTimer3) #if defined(_useTimer3)
SIGNAL (TIMER3_COMPA_vect) SIGNAL (TIMER3_COMPA_vect) { handle_interrupts(_timer3, &TCNT3, &OCR3A); }
{
handle_interrupts(_timer3, &TCNT3, &OCR3A);
}
#endif #endif
#if defined(_useTimer4) #if defined(_useTimer4)
SIGNAL (TIMER4_COMPA_vect) SIGNAL (TIMER4_COMPA_vect) { handle_interrupts(_timer4, &TCNT4, &OCR4A); }
{
handle_interrupts(_timer4, &TCNT4, &OCR4A);
}
#endif #endif
#if defined(_useTimer5) #if defined(_useTimer5)
SIGNAL (TIMER5_COMPA_vect) SIGNAL (TIMER5_COMPA_vect) { handle_interrupts(_timer5, &TCNT5, &OCR5A); }
{
handle_interrupts(_timer5, &TCNT5, &OCR5A);
}
#endif #endif
#elif defined WIRING #else //!WIRING
// Interrupt handlers for Wiring // Interrupt handlers for Wiring
#if defined(_useTimer1) #if defined(_useTimer1)
void Timer1Service() void Timer1Service() { handle_interrupts(_timer1, &TCNT1, &OCR1A); }
{
handle_interrupts(_timer1, &TCNT1, &OCR1A);
}
#endif #endif
#if defined(_useTimer3) #if defined(_useTimer3)
void Timer3Service() void Timer3Service() { handle_interrupts(_timer3, &TCNT3, &OCR3A); }
{
handle_interrupts(_timer3, &TCNT3, &OCR3A);
}
#endif
#endif #endif
#endif //!WIRING
static void initISR(timer16_Sequence_t timer)
{ static void initISR(timer16_Sequence_t timer) {
#if defined(_useTimer1) #if defined(_useTimer1)
if (timer == _timer1) { if (timer == _timer1) {
TCCR1A = 0; // normal counting mode TCCR1A = 0; // normal counting mode
@ -206,36 +189,36 @@ static void initISR(timer16_Sequence_t timer)
#endif #endif
} }
static void finISR(timer16_Sequence_t timer) static void finISR(timer16_Sequence_t timer) {
{ // Disable use of the given timer
//disable use of the given timer #if defined(WIRING)
#if defined WIRING // Wiring
if (timer == _timer1) { if (timer == _timer1) {
#if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) #if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
TIMSK1 &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt TIMSK1
#else #else
TIMSK &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt TIMSK
#endif #endif
&= ~_BV(OCIE1A); // disable timer 1 output compare interrupt
timerDetach(TIMER1OUTCOMPAREA_INT); timerDetach(TIMER1OUTCOMPAREA_INT);
} }
else if (timer == _timer3) { else if (timer == _timer3) {
#if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) #if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
TIMSK3 &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt TIMSK3
#else #else
ETIMSK &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt ETIMSK
#endif #endif
&= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt
timerDetach(TIMER3OUTCOMPAREA_INT); timerDetach(TIMER3OUTCOMPAREA_INT);
} }
#else #else //!WIRING
// 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
#endif #endif
} }
static boolean isTimerActive(timer16_Sequence_t timer) static boolean isTimerActive(timer16_Sequence_t timer) {
{
// returns true if any servo is active on this timer // returns true if any servo is active on this timer
for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) { for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) {
if(SERVO(timer,channel).Pin.isActive == true) if (SERVO(timer,channel).Pin.isActive)
return true; return true;
} }
return false; return false;
@ -244,8 +227,7 @@ static boolean isTimerActive(timer16_Sequence_t timer)
/****************** end of static functions ******************************/ /****************** end of static functions ******************************/
Servo::Servo() Servo::Servo() {
{
if ( ServoCount < MAX_SERVOS) { if ( ServoCount < MAX_SERVOS) {
this->servoIndex = ServoCount++; // assign a servo index to this instance this->servoIndex = ServoCount++; // assign a servo index to this instance
servos[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009 servos[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009
@ -254,13 +236,11 @@ Servo::Servo()
this->servoIndex = INVALID_SERVO; // too many servos this->servoIndex = INVALID_SERVO; // too many servos
} }
uint8_t Servo::attach(int pin) uint8_t Servo::attach(int pin) {
{
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH); return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
} }
uint8_t Servo::attach(int pin, int min, int max) uint8_t Servo::attach(int pin, int min, int max) {
{
if (this->servoIndex < MAX_SERVOS ) { if (this->servoIndex < MAX_SERVOS ) {
#if defined(ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0) #if defined(ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
if (pin > 0) this->pin = pin; else pin = this->pin; if (pin > 0) this->pin = pin; else pin = this->pin;
@ -272,26 +252,20 @@ uint8_t Servo::attach(int pin, int min, int max)
this->max = (MAX_PULSE_WIDTH - max) / 4; this->max = (MAX_PULSE_WIDTH - max) / 4;
// initialize the timer if it has not already been initialized // initialize the timer if it has not already been initialized
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex); timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if(isTimerActive(timer) == false) if (!isTimerActive(timer)) initISR(timer);
initISR(timer);
servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
} }
return this->servoIndex; return this->servoIndex;
} }
void Servo::detach() void Servo::detach() {
{
servos[this->servoIndex].Pin.isActive = false; servos[this->servoIndex].Pin.isActive = false;
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex); timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if(isTimerActive(timer) == false) { if (!isTimerActive(timer)) finISR(timer);
finISR(timer);
}
} }
void Servo::write(int value) 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 < MIN_PULSE_WIDTH)
{ // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
if (value < 0) value = 0; if (value < 0) value = 0;
if (value > 180) value = 180; if (value > 180) value = 180;
value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX()); value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX());
@ -299,12 +273,10 @@ void Servo::write(int value)
this->writeMicroseconds(value); this->writeMicroseconds(value);
} }
void Servo::writeMicroseconds(int value) void Servo::writeMicroseconds(int value) {
{
// calculate and store the values for the given channel // calculate and store the values for the given channel
byte channel = this->servoIndex; byte channel = this->servoIndex;
if( (channel < MAX_SERVOS) ) // ensure channel is valid if (channel < MAX_SERVOS) { // ensure channel is valid
{
if (value < SERVO_MIN()) // ensure pulse width is valid if (value < SERVO_MIN()) // ensure pulse width is valid
value = SERVO_MIN(); value = SERVO_MIN();
else if (value > SERVO_MAX()) else if (value > SERVO_MAX())
@ -320,25 +292,13 @@ void Servo::writeMicroseconds(int value)
} }
} }
int Servo::read() // return the value as degrees // return the value as degrees
{ int Servo::read() { return map( this->readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180); }
return map( this->readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180);
int Servo::readMicroseconds() {
return (this->servoIndex == INVALID_SERVO) ? 0 : ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION;
} }
int Servo::readMicroseconds() bool Servo::attached() { return servos[this->servoIndex].Pin.isActive; }
{
unsigned int pulsewidth;
if( this->servoIndex != INVALID_SERVO )
pulsewidth = ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION ; // 12 aug 2009
else
pulsewidth = 0;
return pulsewidth;
}
bool Servo::attached()
{
return servos[this->servoIndex].Pin.isActive ;
}
#endif #endif

View File

@ -87,6 +87,7 @@ typedef enum { _timer3, _Nbr_16timers } timer16_Sequence_t ;
//#define _useTimer1 //#define _useTimer1
//typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t ; //typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t ;
typedef enum { _Nbr_16timers } timer16_Sequence_t ; typedef enum { _Nbr_16timers } timer16_Sequence_t ;
#endif #endif
#define Servo_VERSION 2 // software version of this library #define Servo_VERSION 2 // software version of this library
@ -111,8 +112,7 @@ typedef struct {
unsigned int ticks; unsigned int ticks;
} servo_t; } servo_t;
class Servo class Servo {
{
public: 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); // attach the given pin to the next free channel, sets pinMode, returns channel number or 0 if failure