#include <Arduino.h>
#include <AccelStepper.h>
#include <string.h>
/*
The step resolution for all drivers : 6400 step/revolution
J1 10:1
J2 25:1
J3 25:1
J4 15:1
J5 9:1
J6 6:1
J2-J3: 230mm
J4-J6: 230mm
Total reach : 460mm
homing:
J1: 40deg from limit
J2: 25deg from limit
J3: 130deg from limit
J4: 150deg from limit
J5: around 90deg from limit
J6: home position at limit
*/
//States Definitions
// #define ESTOP 4
// #define KEYED_SWITCH_L 2
// #define KEYED_SWITCH_R 15
//Steppers Definitions
#define MOTOR_DRIVER 1
#define MAX_ACCELERATION 750
#define MAX_SPEED 3000
//Limit Switches Definitions
#define L1 23
#define L2 22
#define L3 19
#define L4 18
#define L5 15
#define L6 14
AccelStepper J1(MOTOR_DRIVER, 0, 1);
AccelStepper J2(MOTOR_DRIVER, 2, 3);
AccelStepper J3(MOTOR_DRIVER, 4, 5);
AccelStepper J4(MOTOR_DRIVER, 6, 7);
AccelStepper J5(MOTOR_DRIVER, 8, 9);
AccelStepper J6(MOTOR_DRIVER, 10, 11);
long stepsToAngle(double angle, double gearRatio){
const int microstep = 32;
const int stepsPerRev = 200;
double stepsPerDegree = (stepsPerRev * microstep * gearRatio) / 360.0;
return (long)(angle * stepsPerDegree);
}
void homeAllJoints() {
Serial.println("START HOME SEQUENCE");
// Arrays for 5 joints only
AccelStepper* mainJoints[] = {&J2, &J3, &J1};
int mainLimitPins[] = {L2, L3, L1};
double mainRatios[] = {25.0, 25.0, 10.0};
double mainHomePos[] = {25.0, 130.0, 40.0};
for (int i = 0; i < 3; i++){
mainJoints[i]->setSpeed(-2000);
while(digitalRead(mainLimitPins[i]) == LOW){
mainJoints[i]->runSpeed();
}
mainJoints[i]->stop();
delay(200);
mainJoints[i]->setCurrentPosition(0);
long clearance = stepsToAngle(5.0, mainRatios[i]);
mainJoints[i]->moveTo(clearance);
while(mainJoints[i]->distanceToGo() != 0)
mainJoints[i] ->run();
mainJoints[i]->setSpeed(-500);
while (digitalRead(mainLimitPins[i]) == LOW) {
mainJoints[i]->runSpeed();
}
// 4. SET ZERO: This is now the official 0 point
mainJoints[i]->stop();
mainJoints[i]->setCurrentPosition(0);
delay(100);
// 5. MOVE TO HOME POSITION: Move to your desired "Starting Pose"
long homeSteps = stepsToAngle(mainHomePos[i], mainRatios[i]);
mainJoints[i]->moveTo(homeSteps);
// IMPORTANT: Wait for move to finish before starting next joint
while (mainJoints[i]->distanceToGo() != 0) {
mainJoints[i]->run();
}
}
AccelStepper *wristJoints[] = {&J5, &J4};
int wristLimitPins[] = {L5, L4};
double wristRatios[] = {9.0, 15.0};
double wristHomePos[] = {90.0, 150.0};
for (int i = 0; i < 2; i++){
wristJoints[i]->setSpeed(-2000);
while(digitalRead(wristLimitPins[i]) == LOW){
wristJoints[i]->runSpeed();
}
wristJoints[i]->stop();
delay(200);
wristJoints[i]->setCurrentPosition(0);
long clearance = stepsToAngle(5.0, wristRatios[i]);
wristJoints[i]->moveTo(clearance);
while(wristJoints[i]->distanceToGo() != 0)
wristJoints[i] ->run();
wristJoints[i]->setSpeed(-500);
while (digitalRead(wristLimitPins[i]) == LOW) {
wristJoints[i]->runSpeed();
}
// 4. SET ZERO: This is now the official 0 point
wristJoints[i]->stop();
wristJoints[i]->setCurrentPosition(0);
delay(100);
// 5. MOVE TO HOME POSITION: Move to your desired "Starting Pose"
long homeSteps = stepsToAngle(wristHomePos[i], wristRatios[i]);
wristJoints[i]->moveTo(homeSteps);
// IMPORTANT: Wait for move to finish before starting next joint
while (wristJoints[i]->distanceToGo() != 0) {
wristJoints[i]->run();
}
}
J6.setCurrentPosition(0);
Serial.println("HOME SEQUENCE COMPLETE");
}
void setup() {
// put your setup code here, to run once:
Serial.begin(115200);
// Stepper Motors Setup
// Turned the signals into sinking
J1.setAcceleration(MAX_ACCELERATION);
J1.setMaxSpeed(MAX_SPEED);
J1.setPinsInverted(true, false, false);
J2.setAcceleration(MAX_ACCELERATION);
J2.setMaxSpeed(MAX_SPEED);
J2.setPinsInverted(true, false, false);
J3.setAcceleration(MAX_ACCELERATION);
J3.setMaxSpeed(MAX_SPEED);
J3.setPinsInverted(true, false, false);
J4.setAcceleration(MAX_ACCELERATION);
J4.setMaxSpeed(MAX_SPEED);
J4.setPinsInverted(true, false, false);
J5.setAcceleration(MAX_ACCELERATION);
J5.setMaxSpeed(MAX_SPEED);
J5.setPinsInverted(true, false, false);
J6.setAcceleration(MAX_ACCELERATION);
J6.setMaxSpeed(MAX_SPEED);
J6.setPinsInverted(true, false, false);
//Limit Switches Setup
pinMode(L1, INPUT_PULLUP);
pinMode(L2, INPUT_PULLUP);
pinMode(L3, INPUT_PULLUP);
pinMode(L4, INPUT_PULLUP);
pinMode(L5, INPUT_PULLUP);
pinMode(L6, INPUT_PULLUP);
}
void loop() {
// put your main code here, to run repeatedly:
J1.setSpeed(500);
while(digitalRead(L1) == LOW){
J1.runSpeed();
Serial.println(digitalRead(L1));
}
}