better calibration (we should remove the magic #s)
This commit is contained in:
parent
1e8f70f7a9
commit
0ac12e85c4
1 changed files with 17 additions and 13 deletions
|
|
@ -115,7 +115,7 @@ void setup() {
|
|||
// Set electromagnet relay pin as output and ensure it's off initially
|
||||
pinMode(ELECTROMAGNET_RELAY_PIN, OUTPUT);
|
||||
digitalWrite(ELECTROMAGNET_RELAY_PIN, LOW);
|
||||
int initSpeed = 600;
|
||||
int initSpeed = 2000;
|
||||
stepperX.init();
|
||||
stepperX.setMaxSpeed(initSpeed);
|
||||
stepperX.setSpeed(initSpeed);
|
||||
|
|
@ -136,9 +136,7 @@ void setup() {
|
|||
stepperEnd.setMaxSpeed(initSpeed);
|
||||
stepperEnd.setSpeed(initSpeed);
|
||||
stepperEnd.setDirection(-1);
|
||||
// stepperEnd.move(-1200);
|
||||
delay(5000);
|
||||
|
||||
//calibrate each time
|
||||
// if (EEPROM.read(EEPROM_CALIBRATED) != 0xAA) {
|
||||
Serial.println("Calibration needed. Starting");
|
||||
|
|
@ -210,8 +208,8 @@ void calibrateAndHome() {
|
|||
Serial.println("Starting calibration");
|
||||
|
||||
|
||||
// calibrateEndEffectorCarousal();
|
||||
// delay(2500);
|
||||
calibrateEndEffectorCarousal();
|
||||
delay(2500);
|
||||
// moveEffectorIndex(1);
|
||||
// delay(2500);
|
||||
// moveEffectorIndex(2);
|
||||
|
|
@ -225,6 +223,9 @@ void calibrateAndHome() {
|
|||
// moveEffectorIndex(2);
|
||||
// delay(2500);
|
||||
// moveEffectorIndex(0);
|
||||
|
||||
|
||||
|
||||
calibrateXaxis();
|
||||
calculateStepsPerCM();
|
||||
moveToXCM(X_TRAVEL_CM / 2);
|
||||
|
|
@ -232,10 +233,12 @@ void calibrateAndHome() {
|
|||
calibrateZaxis();
|
||||
calculateStepsPerCM();
|
||||
moveToZCM(Z_TRAVEL_CM / 2);
|
||||
delay(2500);
|
||||
|
||||
calibrateYaxis();
|
||||
calculateStepsPerCM();
|
||||
moveToYCM(Y_TRAVEL_CM / 2);
|
||||
delay(2500);
|
||||
|
||||
|
||||
saveCalibrationData();
|
||||
|
|
@ -244,13 +247,13 @@ void calibrateAndHome() {
|
|||
float xCM = 0.0;
|
||||
// moveToHome();
|
||||
// Serial.println("Calibration complete");
|
||||
getCurrentPositionCM(xCM, yCM, zCM);
|
||||
Serial.print("CurrentX ");
|
||||
Serial.print(xCM);
|
||||
Serial.print(" CurrentY ");
|
||||
Serial.print(yCM);
|
||||
Serial.print(" CurrentZ ");
|
||||
Serial.print(zCM);
|
||||
// getCurrentPositionCM(xCM, yCM, zCM);
|
||||
// moveToCM(xCM / 2, yCM / 2, zCM / 2);
|
||||
}
|
||||
|
||||
|
|
@ -298,14 +301,15 @@ void calibrateXaxis(){
|
|||
Serial.println("Calibrating X axis");
|
||||
while (digitalRead(X_MIN_PIN) == HIGH) {
|
||||
stepperX.runSpeed();
|
||||
delay(1);
|
||||
}
|
||||
// stepperX.setCurrentPos(0);
|
||||
xMinSteps = stepperX.currentPosition();
|
||||
Serial.print("X Min: "); Serial.println(xMinSteps);
|
||||
delay(250);
|
||||
stepperX.setDirection(-1);
|
||||
|
||||
|
||||
while (digitalRead(X_MAX_PIN) == HIGH) {
|
||||
stepperX.setDirection(-1);
|
||||
stepperX.runSpeed();
|
||||
}
|
||||
stepperX.setDirection(1);
|
||||
|
|
@ -415,12 +419,12 @@ void calculateStepsPerCM() {
|
|||
// X-axis: Motor steps -> drive gear -> driven gear -> linear motion
|
||||
// Steps per driven gear rotation = motor steps per rotation * 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
|
||||
float yzStepsPerDrivenRotation = STEPS_PER_ROTATION * YZ_GEAR_RATIO;
|
||||
yStepsPerCM = yzStepsPerDrivenRotation / CM_PER_DRIVEN_ROTATION;
|
||||
zStepsPerCM = yzStepsPerDrivenRotation / CM_PER_DRIVEN_ROTATION;
|
||||
yStepsPerCM = (yzStepsPerDrivenRotation / CM_PER_DRIVEN_ROTATION) * 6.75;
|
||||
zStepsPerCM = (yzStepsPerDrivenRotation / CM_PER_DRIVEN_ROTATION) * 6.75;
|
||||
|
||||
Serial.println("Steps per CM calculated:");
|
||||
Serial.print("X-axis: ");
|
||||
|
|
@ -434,7 +438,7 @@ void calculateStepsPerCM() {
|
|||
Serial.println(" steps/cm");
|
||||
|
||||
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_TRAVEL_CM);
|
||||
Serial.println(" cm");
|
||||
|
|
@ -504,7 +508,7 @@ void moveToXCM(float xCM){
|
|||
stepperX.moveTo(xTarget);
|
||||
|
||||
while (stepperX.run()) {
|
||||
stepperX.run();
|
||||
// delay(1);
|
||||
}
|
||||
Serial.println("Move complete");
|
||||
}
|
||||
|
|
|
|||
Loading…
Reference in a new issue