#include <Stepper.h>
const int stepsPerRevolution=2048;
int motSpeed=1;
const int myPotPin=A2;
int readVal;
const int motDir=1;
const int buttonPinSB=6;
const int buttonPinBB=7;
bool buttonSBRead;
bool buttonBBRead;
const int dt=250;
Stepper myStepper(stepsPerRevolution, 8,10,9,11);
volatile unsigned long timer; // all timer variables are unsigned long
volatile int inpulse, seqnr = 20;
volatile int Plist[16];
int pulse, target;
uint8_t mpcount;
int Outpulse[16]; // size equals maximum nr of servo's on Adafruit PCA9685 breakout
const int slowstep = 1, servomax = 8; // number of servos in use
const int targetlow [] = {83, 83, 83, 83, 205, 205, 205, 205};
const int targethigh [] = {467, 467, 467, 467, 410, 410, 410, 410};
#include <Wire.h>
#include <Adafruit_PWMServoDriver.h>
// called this way, it uses the default address 0x40
Adafruit_PWMServoDriver pwm = Adafruit_PWMServoDriver();
void setup() {
attachInterrupt(0, read_pwm, CHANGE); // Pin 2 = interrupt 0
pinMode(2, INPUT);
Serial.begin(9600);
pwm.begin();
pwm.setOscillatorFrequency(27000000);
pwm.setPWMFreq(50); // 50Hz, frame length 20 millis
// starting output pulse value, equivalent of 1500 micros
for (uint8_t i=0; i<servomax; i++) {
Outpulse [i] = 308;
pwm.setPWM(i, 0, Outpulse [i]);
}
{
myStepper.setSpeed(motSpeed);
pinMode(buttonPinSB, INPUT_PULLUP);
pinMode(buttonPinBB, INPUT_PULLUP);
}
delay(10);
}
void loop() {
for (mpcount = 0; mpcount < servomax; mpcount ++) {
cli(); // stop interrupt interference
pulse = Plist[mpcount]; // get latest pulse
sei(); // release interrupt
//Serial.print ("mpcount = "); Serial.print (mpcount); Serial.print (" pulse = "); Serial.println (pulse);
target = map (pulse, 1030, 1980, targetlow [mpcount], targethigh [mpcount]); // extending pulse to target
// retrieve previous Outpulse and calculate new value for Outpulse
if ((target - Outpulse [mpcount]) >= slowstep) Outpulse [mpcount] += slowstep;
else if ((target - Outpulse [mpcount]) <= -slowstep) Outpulse [mpcount] -= slowstep;
else Outpulse [mpcount] = target;
// send Outpulse
pwm.setPWM(mpcount, 0, Outpulse [mpcount]); // LOW>HIGH at 0, HIGH>LOW at pulselen
}
delay (10); // change to decrease servo speed.
buttonSBRead=digitalRead(buttonPinSB);
buttonBBRead=digitalRead(buttonPinBB);
//delay(dt);
readVal=analogRead (myPotPin); // uitlezen van de waarde van de potentiometer met min = 70 en max = 1010
//Serial.print ("Potval = ");
//Serial.print (readVal);
//Serial.print(" SBbutton = ");
//Serial.print(buttonSBRead);
//Serial.print(" BBbutton = ");
//Serial.println(buttonBBRead);
//delay(dt);
if (readVal <=300 && buttonSBRead==1){
myStepper.step(motDir*-1);
}
if (readVal >=530 && buttonBBRead==1){
myStepper.step(motDir*1);
}
void read_pwm(){
if (PIND & 0b00000100) { // if pin 2 is high
timer = micros(); // start timer
}
else { // else pin 2 is low
inpulse = ((volatile int)micros() - timer); // read timer
if (inpulse<950) seqnr = -1; // reset seqnr for next incoming pulses to start with 0
else {
seqnr += 1;
if (seqnr < 16) Plist[seqnr] = inpulse;
}
}
}