better calibration (we should remove the magic #s)

This commit is contained in:
2ManyProjects 2025-09-19 01:00:15 -05:00
parent 1e8f70f7a9
commit 0ac12e85c4

View file

@ -115,7 +115,7 @@ void setup() {
// Set electromagnet relay pin as output and ensure it's off initially // Set electromagnet relay pin as output and ensure it's off initially
pinMode(ELECTROMAGNET_RELAY_PIN, OUTPUT); pinMode(ELECTROMAGNET_RELAY_PIN, OUTPUT);
digitalWrite(ELECTROMAGNET_RELAY_PIN, LOW); digitalWrite(ELECTROMAGNET_RELAY_PIN, LOW);
int initSpeed = 600; int initSpeed = 2000;
stepperX.init(); stepperX.init();
stepperX.setMaxSpeed(initSpeed); stepperX.setMaxSpeed(initSpeed);
stepperX.setSpeed(initSpeed); stepperX.setSpeed(initSpeed);
@ -136,9 +136,7 @@ void setup() {
stepperEnd.setMaxSpeed(initSpeed); stepperEnd.setMaxSpeed(initSpeed);
stepperEnd.setSpeed(initSpeed); stepperEnd.setSpeed(initSpeed);
stepperEnd.setDirection(-1); stepperEnd.setDirection(-1);
// stepperEnd.move(-1200);
delay(5000); delay(5000);
//calibrate each time //calibrate each time
// if (EEPROM.read(EEPROM_CALIBRATED) != 0xAA) { // if (EEPROM.read(EEPROM_CALIBRATED) != 0xAA) {
Serial.println("Calibration needed. Starting"); Serial.println("Calibration needed. Starting");
@ -210,8 +208,8 @@ void calibrateAndHome() {
Serial.println("Starting calibration"); Serial.println("Starting calibration");
// calibrateEndEffectorCarousal(); calibrateEndEffectorCarousal();
// delay(2500); delay(2500);
// moveEffectorIndex(1); // moveEffectorIndex(1);
// delay(2500); // delay(2500);
// moveEffectorIndex(2); // moveEffectorIndex(2);
@ -225,6 +223,9 @@ void calibrateAndHome() {
// moveEffectorIndex(2); // moveEffectorIndex(2);
// delay(2500); // delay(2500);
// moveEffectorIndex(0); // moveEffectorIndex(0);
calibrateXaxis(); calibrateXaxis();
calculateStepsPerCM(); calculateStepsPerCM();
moveToXCM(X_TRAVEL_CM / 2); moveToXCM(X_TRAVEL_CM / 2);
@ -232,10 +233,12 @@ void calibrateAndHome() {
calibrateZaxis(); calibrateZaxis();
calculateStepsPerCM(); calculateStepsPerCM();
moveToZCM(Z_TRAVEL_CM / 2); moveToZCM(Z_TRAVEL_CM / 2);
delay(2500);
calibrateYaxis(); calibrateYaxis();
calculateStepsPerCM(); calculateStepsPerCM();
moveToYCM(Y_TRAVEL_CM / 2); moveToYCM(Y_TRAVEL_CM / 2);
delay(2500);
saveCalibrationData(); saveCalibrationData();
@ -244,13 +247,13 @@ void calibrateAndHome() {
float xCM = 0.0; float xCM = 0.0;
// moveToHome(); // moveToHome();
// Serial.println("Calibration complete"); // Serial.println("Calibration complete");
getCurrentPositionCM(xCM, yCM, zCM);
Serial.print("CurrentX "); Serial.print("CurrentX ");
Serial.print(xCM); Serial.print(xCM);
Serial.print(" CurrentY "); Serial.print(" CurrentY ");
Serial.print(yCM); Serial.print(yCM);
Serial.print(" CurrentZ "); Serial.print(" CurrentZ ");
Serial.print(zCM); Serial.print(zCM);
// getCurrentPositionCM(xCM, yCM, zCM);
// moveToCM(xCM / 2, yCM / 2, zCM / 2); // moveToCM(xCM / 2, yCM / 2, zCM / 2);
} }
@ -298,14 +301,15 @@ void calibrateXaxis(){
Serial.println("Calibrating X axis"); Serial.println("Calibrating X axis");
while (digitalRead(X_MIN_PIN) == HIGH) { while (digitalRead(X_MIN_PIN) == HIGH) {
stepperX.runSpeed(); stepperX.runSpeed();
delay(1);
} }
// stepperX.setCurrentPos(0);
xMinSteps = stepperX.currentPosition(); xMinSteps = stepperX.currentPosition();
Serial.print("X Min: "); Serial.println(xMinSteps); Serial.print("X Min: "); Serial.println(xMinSteps);
delay(250);
stepperX.setDirection(-1);
while (digitalRead(X_MAX_PIN) == HIGH) { while (digitalRead(X_MAX_PIN) == HIGH) {
stepperX.setDirection(-1);
stepperX.runSpeed(); stepperX.runSpeed();
} }
stepperX.setDirection(1); stepperX.setDirection(1);
@ -415,12 +419,12 @@ void calculateStepsPerCM() {
// X-axis: Motor steps -> drive gear -> driven gear -> linear motion // X-axis: Motor steps -> drive gear -> driven gear -> linear motion
// Steps per driven gear rotation = motor steps per rotation * gear ratio // Steps per driven gear rotation = motor steps per rotation * gear ratio
float xStepsPerDrivenRotation = STEPS_PER_ROTATION * X_GEAR_RATIO; float xStepsPerDrivenRotation = STEPS_PER_ROTATION * X_GEAR_RATIO;
xStepsPerCM = xStepsPerDrivenRotation / CM_PER_DRIVEN_ROTATION; xStepsPerCM = (xStepsPerDrivenRotation / (1.0 / (THREAD_ROTATIONS_PER_CM ))) * 10;
// Y and Z axis // Y and Z axis
float yzStepsPerDrivenRotation = STEPS_PER_ROTATION * YZ_GEAR_RATIO; float yzStepsPerDrivenRotation = STEPS_PER_ROTATION * YZ_GEAR_RATIO;
yStepsPerCM = yzStepsPerDrivenRotation / CM_PER_DRIVEN_ROTATION; yStepsPerCM = (yzStepsPerDrivenRotation / CM_PER_DRIVEN_ROTATION) * 6.75;
zStepsPerCM = yzStepsPerDrivenRotation / CM_PER_DRIVEN_ROTATION; zStepsPerCM = (yzStepsPerDrivenRotation / CM_PER_DRIVEN_ROTATION) * 6.75;
Serial.println("Steps per CM calculated:"); Serial.println("Steps per CM calculated:");
Serial.print("X-axis: "); Serial.print("X-axis: ");
@ -434,7 +438,7 @@ void calculateStepsPerCM() {
Serial.println(" steps/cm"); Serial.println(" steps/cm");
if (xMaxSteps != 0 || xMinSteps != 0) { if (xMaxSteps != 0 || xMinSteps != 0) {
X_TRAVEL_CM = abs(xMaxSteps - xMinSteps) / xStepsPerCM; X_TRAVEL_CM = (abs(xMaxSteps - xMinSteps) / xStepsPerCM);
Serial.print("X-axis total travel: "); Serial.print("X-axis total travel: ");
Serial.print(X_TRAVEL_CM); Serial.print(X_TRAVEL_CM);
Serial.println(" cm"); Serial.println(" cm");
@ -504,7 +508,7 @@ void moveToXCM(float xCM){
stepperX.moveTo(xTarget); stepperX.moveTo(xTarget);
while (stepperX.run()) { while (stepperX.run()) {
stepperX.run(); // delay(1);
} }
Serial.println("Move complete"); Serial.println("Move complete");
} }