Skip to content

Commit

Permalink
Updates to Servo library from Oliver.
Browse files Browse the repository at this point in the history
Former-commit-id: a5f7096
  • Loading branch information
ricklon committed Jul 31, 2011
1 parent bce6ad1 commit 30e030a
Show file tree
Hide file tree
Showing 4 changed files with 29 additions and 22 deletions.
46 changes: 27 additions & 19 deletions hardware/pic32/libraries/Servo/Servo.cpp
Expand Up @@ -25,7 +25,7 @@ extern "C"{


static servo_t servos[MAX_SERVOS]; // static array of servo structures
int channel[1]; //channel for the current servo
int channel[3]; //channel for the current servo

uint8_t ServoCount = 0; // the total number of attached servos

Expand All @@ -37,7 +37,7 @@ uint8_t ServoCount = 0; // the total number
#define SERVO(_timer,_channel) (servos[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel
/************ static functions common to all instances ***********************/

void handle_interrupts(int timer, volatile unsigned int *TMRn, volatile unsigned int *OCnR)
void handle_interrupts(int timer, volatile unsigned int *TMRn, volatile unsigned int *PR)
{


Expand All @@ -50,16 +50,17 @@ void handle_interrupts(int timer, volatile unsigned int *TMRn, volatile unsigned

channel[timer]++; // increment to the next channel
if( SERVO_INDEX(timer,channel[timer]) < ServoCount && channel[timer] < SERVOS_PER_TIMER) {
*OCnR = *TMRn + SERVO(timer,channel[timer]).ticks;
*PR = *TMRn + 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 {
*TMRn = channel[timer] * usToTicks(MAX_PULSE_WIDTH);
// finished all channels so wait for the refresh period to expire before starting over
if( (unsigned)*TMRn < (usToTicks(REFRESH_INTERVAL) + 4) ) // allow a few ticks to ensure the next OCR1A not missed
*OCnR = (unsigned int)usToTicks(REFRESH_INTERVAL);
*PR = (unsigned int)usToTicks(REFRESH_INTERVAL);
else
*OCnR = *TMRn + 4; // at least REFRESH_INTERVAL has elapsed
*PR = *TMRn + 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
}

Expand All @@ -72,9 +73,17 @@ void handle_interrupts(int timer, volatile unsigned int *TMRn, volatile unsigned
static void finISR(int timer)
{
//disable use of the given timer
if(timer = TIMER2)
if(timer = TIMER3)
{
IEC0CLR = 0x400000;// disable OC5 interrupt
IEC0CLR = 0x1000;// disable T4 interrupt
}
if(timer = TIMER4)
{
IEC0CLR = 0x10000;// disable T4 interrupt
}
if(timer = TIMER5)
{
IEC0CLR = 0x100000;// disable T5 interrupt
}

}
Expand Down Expand Up @@ -115,18 +124,17 @@ uint8_t Servo::attach(int pin, int min, int max)
U1MODE = 0x0;

}
if(pin != 10) // pin 10 is tied to OC5 can't use as an output
{
pinMode( pin, OUTPUT) ; // set servo pin to output
servos[this->servoIndex].Pin.nbr = pin;
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
int timer = SERVO_INDEX_TO_TIMER(this->servoIndex);
if(isTimerActive(timer) == false)
initISR(timer);
servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
}

pinMode( pin, OUTPUT) ; // set servo pin to output
servos[this->servoIndex].Pin.nbr = pin;
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
int timer = SERVO_INDEX_TO_TIMER(this->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 ;
}
}
Expand Down
2 changes: 1 addition & 1 deletion hardware/pic32/libraries/Servo/Servo.h
Expand Up @@ -58,7 +58,7 @@
#define Servo_VERSION 3 // software version of this library

#define SERVOS_PER_TIMER 8 // the maximum number of servos controlled by one timer
#define MAX_SERVOS 8
#define MAX_SERVOS 24


#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo (us)
Expand Down
1 change: 0 additions & 1 deletion hardware/pic32/libraries/Servo/examples/Knob/Knob.pde
Expand Up @@ -2,7 +2,6 @@
// by Michal Rinott <http://people.interaction-ivrea.it/m.rinott>

// NOTE: UART will be disabled when servo is attached to pin 0 or 1.
// Due to the use of OC5, Servo will not work when attach to pin 10.


#include <Servo.h>
Expand Down
2 changes: 1 addition & 1 deletion hardware/pic32/libraries/Servo/examples/Sweep/Sweep.pde
Expand Up @@ -3,7 +3,7 @@
// This example code is in the public domain.

// NOTE: UART will be disabled when servo is attached to pin 0 or 1.
// Due to the use of OC5, Servo will not work when attach to pin 10.


#include <Servo.h>

Expand Down

0 comments on commit 30e030a

Please sign in to comment.