debugging axis class
parent
cc0be05174
commit
890ff84385
|
@ -44,6 +44,7 @@ int G00Handler::execute(Command* command) {
|
|||
command->getX(), command->getY(), command->getZ(),
|
||||
command->getA(), command->getB(), command->getC(),
|
||||
false, false, false);
|
||||
|
||||
if (LOGGING) {
|
||||
CurrentState::getInstance()->print();
|
||||
}
|
||||
|
|
|
@ -14,13 +14,20 @@ StepperControl * StepperControl::getInstance() {
|
|||
const int MOVEMENT_INTERRUPT_SPEED = 100; // Interrupt cycle in micro seconds
|
||||
|
||||
StepperControl::StepperControl() {
|
||||
|
||||
axisX = StepperControlAxis();
|
||||
axisY = StepperControlAxis();
|
||||
axisZ = StepperControlAxis();
|
||||
|
||||
axisX.label = 'X';
|
||||
axisY.label = 'Y';
|
||||
axisZ.label = 'Z';
|
||||
|
||||
axisX.loadPinNumbers(X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN);
|
||||
axisY.loadPinNumbers(Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN);
|
||||
axisZ.loadPinNumbers(Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN);
|
||||
|
||||
loadMotorSettings();
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -37,7 +44,6 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
|
|||
unsigned long currentMillis = 0;
|
||||
unsigned long timeStart = millis();
|
||||
|
||||
|
||||
int incomingByte = 0;
|
||||
int error = 0;
|
||||
|
||||
|
@ -47,11 +53,6 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
|
|||
|
||||
// if a speed is given in the command, use that instead of the config speed
|
||||
|
||||
long speedMax[3] = {0,0,0};
|
||||
speedMax[0] = xMaxSpd;
|
||||
speedMax[1] = yMaxSpd;
|
||||
speedMax[2] = zMaxSpd;
|
||||
|
||||
if (xMaxSpd > 0 && xMaxSpd < speedMax[0]) {
|
||||
speedMax[0] = xMaxSpd;
|
||||
}
|
||||
|
@ -64,7 +65,6 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
|
|||
speedMax[2] = zMaxSpd;
|
||||
}
|
||||
|
||||
|
||||
axisX.setMaxSpeed(speedMax[0]);
|
||||
axisY.setMaxSpeed(speedMax[1]);
|
||||
axisZ.setMaxSpeed(speedMax[2]);
|
||||
|
@ -94,13 +94,14 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
|
|||
|
||||
// Prepare for movement
|
||||
|
||||
//axisX.setDirection()
|
||||
//axisY.setDirection()
|
||||
//axisZ.setDirection()
|
||||
|
||||
storeEndStops();
|
||||
reportEndStops();
|
||||
|
||||
|
||||
axisX.setDirectionAxis();
|
||||
axisY.setDirectionAxis();
|
||||
axisZ.setDirectionAxis();
|
||||
|
||||
enableMotors();
|
||||
|
||||
// Start movement
|
||||
|
@ -109,9 +110,13 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
|
|||
axisActive[1] = true;
|
||||
axisActive[2] = true;
|
||||
|
||||
//axisActive[0] = false;
|
||||
axisActive[1] = false;
|
||||
axisActive[2] = false;
|
||||
|
||||
axisX.checkMovement();
|
||||
// axisY.checkMovement();
|
||||
// axisZ.checkMovement();
|
||||
//axisY.checkMovement();
|
||||
//axisZ.checkMovement();
|
||||
|
||||
//Timer1.start();
|
||||
|
||||
|
@ -120,19 +125,19 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
|
|||
|
||||
//delay(50);
|
||||
delayMicroseconds(100);
|
||||
/*
|
||||
Serial.print("R99 ");
|
||||
Serial.print(" x axis active ");
|
||||
Serial.print(axisActive[0]);
|
||||
Serial.print(" y axis active ");
|
||||
Serial.print(axisActive[1]);
|
||||
Serial.print(" z axis active ");
|
||||
Serial.print(axisActive[2]);
|
||||
Serial.print("\n");
|
||||
*/
|
||||
|
||||
// Serial.print("R99 ");
|
||||
// Serial.print(" x axis active ");
|
||||
// Serial.print(axisActive[0]);
|
||||
// Serial.print(" y axis active ");
|
||||
// Serial.print(axisActive[1]);
|
||||
// Serial.print(" z axis active ");
|
||||
// Serial.print(axisActive[2]);
|
||||
// Serial.print("\n");
|
||||
|
||||
axisX.checkTiming();
|
||||
axisY.checkTiming();
|
||||
axisZ.checkTiming();
|
||||
//axisY.checkTiming();
|
||||
//axisZ.checkTiming();
|
||||
|
||||
axisActive[0] = axisX.isAxisActive();
|
||||
axisActive[1] = axisY.isAxisActive();
|
||||
|
@ -180,9 +185,9 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
|
|||
|
||||
}
|
||||
|
||||
/**/Serial.print("R99 stopped\n");
|
||||
Serial.print("R99 stopped\n");
|
||||
|
||||
Timer1.stop();
|
||||
//Timer1.stop();
|
||||
disableMotors();
|
||||
|
||||
currentPoint[0] = axisX.currentPoint();
|
||||
|
@ -615,4 +620,9 @@ void StepperControl::loadMotorSettings() {
|
|||
timeOut[0] = ParameterList::getInstance()->getValue(MOVEMENT_TIMEOUT_X);
|
||||
timeOut[1] = ParameterList::getInstance()->getValue(MOVEMENT_TIMEOUT_X);
|
||||
timeOut[2] = ParameterList::getInstance()->getValue(MOVEMENT_TIMEOUT_X);
|
||||
|
||||
axisX.loadMotorSettings(speedMax[0], speedMin[0], stepsAcc[0], timeOut[0], homeIsUp[0], motorInv[0], endStInv[0], MOVEMENT_INTERRUPT_SPEED);
|
||||
axisY.loadMotorSettings(speedMax[1], speedMin[1], stepsAcc[1], timeOut[1], homeIsUp[1], motorInv[1], endStInv[1], MOVEMENT_INTERRUPT_SPEED);
|
||||
axisZ.loadMotorSettings(speedMax[2], speedMin[2], stepsAcc[2], timeOut[2], homeIsUp[2], motorInv[2], endStInv[2], MOVEMENT_INTERRUPT_SPEED);
|
||||
|
||||
}
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
#include "StepperControlAxis.h"
|
||||
|
||||
//int test = 0;
|
||||
|
||||
long interruptSpeed = 100;
|
||||
|
||||
StepperControlAxis::StepperControlAxis() {
|
||||
|
@ -15,6 +13,12 @@ StepperControlAxis::StepperControlAxis() {
|
|||
|
||||
}
|
||||
|
||||
void StepperControlAxis::test() {
|
||||
Serial.print("R99 ");
|
||||
Serial.print(label);
|
||||
Serial.print("\n");
|
||||
}
|
||||
|
||||
unsigned int StepperControlAxis::calculateSpeed(long sourcePosition, long currentPosition, long destinationPosition, long minSpeed, long maxSpeed, long stepsAccDec) {
|
||||
|
||||
int newSpeed = 0;
|
||||
|
@ -102,6 +106,7 @@ unsigned int StepperControlAxis::calculateSpeed(long sourcePosition, long curren
|
|||
}
|
||||
|
||||
void StepperControlAxis::checkAxisDirection() {
|
||||
|
||||
if (coordHomeAxis){
|
||||
// When home is active, the direction is fixed
|
||||
movementUp = motorHomeIsUp;
|
||||
|
@ -129,62 +134,16 @@ void StepperControlAxis::setDirectionAxis() {
|
|||
|
||||
void StepperControlAxis::checkMovement() {
|
||||
|
||||
int i = 1;
|
||||
|
||||
//moveTicks[i]++;
|
||||
checkAxisDirection();
|
||||
|
||||
|
||||
|
||||
Serial.print("R99 check axis ");
|
||||
Serial.print(axisActive);
|
||||
Serial.print(" current point ");
|
||||
Serial.print(coordCurrentPoint);
|
||||
Serial.print(" destination point ");
|
||||
Serial.print(coordDestinationPoint);
|
||||
|
||||
Serial.print(" home stop reached ");
|
||||
Serial.print(endStopAxisReached(false));
|
||||
Serial.print(" axis stop reached ");
|
||||
Serial.print(endStopAxisReached(true));
|
||||
Serial.print(" home axis ");
|
||||
Serial.print(coordHomeAxis);
|
||||
Serial.print(" movement to home ");
|
||||
Serial.print(movementToHome);
|
||||
Serial.print("\n");
|
||||
|
||||
|
||||
|
||||
//if ((!pointReached(currentPoint, destinationPoint) || home) && axisActive[i]) {
|
||||
if (((coordCurrentPoint != coordDestinationPoint) || coordHomeAxis) && axisActive) {
|
||||
//Serial.print("R99 point not reached yet\n");
|
||||
|
||||
// home or destination not reached, keep moving
|
||||
/*
|
||||
Serial.print("R99 calc axis speed");
|
||||
Serial.print(" speed max ");
|
||||
Serial.print(speedMax[i]);
|
||||
Serial.print("\n");
|
||||
*/
|
||||
|
||||
// Get the axis speed, in steps per second
|
||||
axisSpeed = calculateSpeed( coordSourcePoint, coordCurrentPoint, coordDestinationPoint,
|
||||
motorSpeedMin, motorSpeedMax, motorStepsAcc);
|
||||
|
||||
//Serial.print("R99 axis speed ");
|
||||
//Serial.print(axisSpeed[i]);
|
||||
//Serial.print("\n");
|
||||
|
||||
/*
|
||||
Serial.print("R99 check axis b ");
|
||||
Serial.print(i);
|
||||
Serial.print(" home part true ");
|
||||
Serial.print(homeAxis[i] && !endStopAxisReached(i, false));
|
||||
Serial.print(" !homeAxis[i] ");
|
||||
Serial.print(!homeAxis[i]);
|
||||
Serial.print(" !endStopAxisReached(i, !movementToHome[i]) ");
|
||||
Serial.print(!endStopAxisReached(i, !movementToHome[i]));
|
||||
Serial.print("\n");
|
||||
*/
|
||||
// If end stop reached, don't move anymore
|
||||
if ((coordHomeAxis && !endStopAxisReached(false)) || (!coordHomeAxis && !endStopAxisReached(!movementToHome))) {
|
||||
|
||||
|
@ -197,7 +156,6 @@ Serial.print("\n");
|
|||
// This gives the number of interrupts (called ticks here) before the pulse needs to be set for the next step
|
||||
stepOnTick = moveTicks + (1000.0 * 1000.0 / interruptSpeed / axisSpeed / 2);
|
||||
stepOffTick = moveTicks + (1000.0 * 1000.0 / interruptSpeed / axisSpeed );
|
||||
|
||||
}
|
||||
}
|
||||
else {
|
||||
|
@ -213,8 +171,6 @@ Serial.print("\n");
|
|||
if (endStopAxisReached(false)) {
|
||||
coordCurrentPoint = 0;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
void StepperControlAxis::checkTiming() {
|
||||
|
@ -225,12 +181,7 @@ void StepperControlAxis::checkTiming() {
|
|||
|
||||
if (axisActive) {
|
||||
if (moveTicks >= stepOffTick) {
|
||||
/*
|
||||
Serial.print("R99 reset step ");
|
||||
Serial.print(" moveTicks ");
|
||||
Serial.print(moveTicks);
|
||||
Serial.print("\n");
|
||||
*/
|
||||
|
||||
// Negative flank for the steps
|
||||
resetMotorStep();
|
||||
checkMovement();
|
||||
|
@ -238,12 +189,7 @@ Serial.print("\n");
|
|||
else {
|
||||
|
||||
if (moveTicks == stepOnTick) {
|
||||
/*
|
||||
Serial.print("R99 set step ");
|
||||
Serial.print(" moveTicks ");
|
||||
Serial.print(moveTicks);
|
||||
Serial.print("\n");
|
||||
*/
|
||||
|
||||
// Positive flank for the steps
|
||||
setStepAxis();
|
||||
}
|
||||
|
@ -351,26 +297,26 @@ void StepperControlAxis::loadCoordinates(long sourcePoint, long destinationPoint
|
|||
}
|
||||
|
||||
void StepperControlAxis::enableMotor() {
|
||||
digitalWrite(pinEnable, HIGH);
|
||||
digitalWrite(pinEnable, LOW);
|
||||
}
|
||||
|
||||
void StepperControlAxis::disableMotor() {
|
||||
digitalWrite(pinEnable, LOW);
|
||||
digitalWrite(pinEnable, HIGH);
|
||||
}
|
||||
|
||||
void StepperControlAxis::setDirectionUp() {
|
||||
if (motorMotorInv) {
|
||||
digitalWrite(pinDirection, HIGH);
|
||||
} else {
|
||||
digitalWrite(pinDirection, LOW);
|
||||
} else {
|
||||
digitalWrite(pinDirection, HIGH);
|
||||
}
|
||||
}
|
||||
|
||||
void StepperControlAxis::setDirectionDown() {
|
||||
if (motorMotorInv) {
|
||||
digitalWrite(pinDirection, LOW);
|
||||
} else {
|
||||
digitalWrite(pinDirection, HIGH);
|
||||
} else {
|
||||
digitalWrite(pinDirection, LOW);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -403,10 +349,12 @@ bool StepperControlAxis::endStopsReached() {
|
|||
}
|
||||
|
||||
bool StepperControlAxis::endStopMin() {
|
||||
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
|
||||
return digitalRead(pinMin);
|
||||
}
|
||||
|
||||
bool StepperControlAxis::endStopMax() {
|
||||
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
|
||||
return digitalRead(pinMax);
|
||||
}
|
||||
|
||||
|
|
|
@ -46,6 +46,11 @@ public:
|
|||
void setDirectionDown();
|
||||
void setDirectionHome();
|
||||
void setDirectionAway();
|
||||
void setDirectionAxis();
|
||||
|
||||
void test();
|
||||
|
||||
char label;
|
||||
|
||||
private:
|
||||
|
||||
|
@ -89,7 +94,6 @@ private:
|
|||
void step(long ¤tPoint, unsigned long steps, long destinationPoint);
|
||||
bool pointReached(long currentPoint, long destinationPoint);
|
||||
unsigned int calculateSpeed(long sourcePosition, long currentPosition, long destinationPosition, long minSpeed, long maxSpeed, long stepsAccDec);
|
||||
void setDirectionAxis();
|
||||
unsigned long getLength(long l1, long l2);
|
||||
void checkAxisDirection();
|
||||
|
||||
|
|
Loading…
Reference in New Issue