Added timer 2 as interrupt for motor timing

Direction fixed
pull/118/head
Tim Evers 2019-03-30 22:24:49 +01:00
parent 665de68b7e
commit 3e2a0276c3
6 changed files with 242 additions and 115 deletions

View File

@ -173,18 +173,31 @@ void StepperControl::loadSettings()
encoderY.loadSettings(motorConsEncoderType[1], motorConsEncoderScaling[1], motorConsEncoderInvert[1]);
encoderZ.loadSettings(motorConsEncoderType[2], motorConsEncoderScaling[2], motorConsEncoderInvert[2]);
/**/
#if defined(FARMDUINO_EXP_V20)
axisX.initTMC2130A();
#endif
}
#if defined(FARMDUINO_EXP_V20)
void StepperControl::initTMC2130A()
{
/**/
axisX.initTMC2130A();
//axisY.initTMC2130A();
//axisZ.initTMC2130A();
}
#endif
void StepperControl::test()
{
axisX.enableMotor();
axisX.setMotorStep();
//axisX.enableMotor();
//axisX.setMotorStep();
//digitalWrite(X_STEP_PIN, HIGH);
//delayMicroseconds(10);
//digitalWrite(X_STEP_PIN, LOW);
//delayMicroseconds(10);
//axisX.setMotorStepWriteTMC2130();
//axisX.test();
//Serial.print("R99");
//Serial.print(" mot x = ");
@ -400,7 +413,14 @@ int StepperControl::moveToCoords(double xDestScaled, double yDestScaled, double
{
/**/ //axisX.setMotorStep();
/**/ //delayMicroseconds(10);
//!@#$
//#if defined(FARMDUINO_EXP_V20)
//axisX.incrementTick();
//axisY.incrementTick();
//axisZ.incrementTick();
//#endif
#if defined(FARMDUINO_V14)
checkEncoders();
#endif
@ -417,7 +437,6 @@ int StepperControl::moveToCoords(double xDestScaled, double yDestScaled, double
if (axisX.isStepDone())
{
/**/
axisX.checkMovement();
checkAxisVsEncoder(&axisX, &encoderX, &motorConsMissedSteps[0], &motorLastPosition[0], &motorConsEncoderLastPosition[0], &motorConsEncoderUseForPos[0], &motorConsMissedStepsDecay[0], &motorConsEncoderEnabled[0]);
axisX.resetStepDone();

View File

@ -37,6 +37,11 @@ public:
void handleMovementInterrupt();
void checkEncoders();
#if defined(FARMDUINO_EXP_V20)
void initTMC2130A();
#endif
int calibrateAxis(int axis);
//void initInterrupt();
void enableMotors();

View File

@ -1,13 +1,15 @@
#include "StepperControlAxis.h"
#include <TMC2130Stepper.h>
//#include <TMC2130Stepper.h>
#if defined(FARMDUINO_EXP_V20)
TMC2130Stepper TMC2130X = TMC2130Stepper(X_ENABLE_PIN, X_DIR_PIN, X_STEP_PIN, X_CHIP_SELECT);
TMC2130Stepper TMC2130Y = TMC2130Stepper(Y_ENABLE_PIN, Y_DIR_PIN, Y_STEP_PIN, Y_CHIP_SELECT);
TMC2130Stepper TMC2130Z = TMC2130Stepper(Z_ENABLE_PIN, Z_DIR_PIN, Z_STEP_PIN, Z_CHIP_SELECT);
TMC2130Stepper TMC2130E = TMC2130Stepper(E_ENABLE_PIN, E_DIR_PIN, E_STEP_PIN, E_CHIP_SELECT);
static TMC2130Stepper TMC2130X = TMC2130Stepper(X_ENABLE_PIN, X_DIR_PIN, X_STEP_PIN, X_CHIP_SELECT);
static TMC2130Stepper TMC2130Y = TMC2130Stepper(Y_ENABLE_PIN, Y_DIR_PIN, Y_STEP_PIN, Y_CHIP_SELECT);
static TMC2130Stepper TMC2130Z = TMC2130Stepper(Z_ENABLE_PIN, Z_DIR_PIN, Z_STEP_PIN, Z_CHIP_SELECT);
static TMC2130Stepper TMC2130E = TMC2130Stepper(E_ENABLE_PIN, E_DIR_PIN, E_STEP_PIN, E_CHIP_SELECT);
#endif
StepperControlAxis::StepperControlAxis()
{
lastCalcLog = 0;
@ -46,6 +48,8 @@ StepperControlAxis::StepperControlAxis()
resetMotorStepWrite = &StepperControlAxis::resetMotorStepWriteDefault;
resetMotorStepWrite2 = &StepperControlAxis::resetMotorStepWriteDefault2;
/**/
/*
#if defined(FARMDUINO_EXP_V20)
//// TMC2130 Functions
@ -54,48 +58,68 @@ StepperControlAxis::StepperControlAxis()
resetMotorStepWrite = &StepperControlAxis::resetMotorStepWriteTMC2130;
resetMotorStepWrite2 = &StepperControlAxis::resetMotorStepWriteTMC2130_2;
#endif
*/
}
void StepperControlAxis::test()
{
Serial.print("R99");
Serial.print(" cur loc = ");
Serial.print(coordCurrentPoint);
//setMotorStep();
//setMotorStepWriteTMC2130();
//Serial.print("R99");
//Serial.print(" cur loc = ");
//Serial.print(coordCurrentPoint);
//Serial.print(" enc loc = ");
//Serial.print(coordEncoderPoint);
//Serial.print(" cons steps missed = ");
//Serial.print(label);
//Serial.print(consMissedSteps);
Serial.print("\r\n");
//Serial.print("\r\n");
}
#if defined(FARMDUINO_EXP_V20)
void StepperControlAxis::initTMC2130A()
{
/*
TMC2130X.begin(); // Initiate pins and registeries
TMC2130X.SilentStepStick2130(600); // Set stepper current to 600mA
TMC2130X.stealthChop(1); // Enable extremely quiet stepping
TMC2130X.shaft_dir(0);
*/
/**/
if (channelLabel == 'X')
{
TMC2130X.begin(); // Initiate pins and registeries
TMC2130X.SilentStepStick2130(600); // Set stepper current to 600mA
TMC2130X.stealthChop(1); // Enable extremely quiet stepping
TMC2130E.begin(); // Initiate pins and registeries
TMC2130E.SilentStepStick2130(600); // Set stepper current to 600mA
TMC2130E.stealthChop(1); // Enable extremely quiet stepping
TMC2130A = &TMC2130X;
TMC2130B = &TMC2130E;
}
if (channelLabel == 'Y')
{
TMC2130X.begin(); // Initiate pins and registeries
TMC2130X.SilentStepStick2130(600); // Set stepper current to 600mA
TMC2130X.stealthChop(1); // Enable extremely quiet stepping
TMC2130A = &TMC2130Y;
}
if (channelLabel == 'Z')
{
TMC2130Z.begin(); // Initiate pins and registeries
TMC2130Z.SilentStepStick2130(600); // Set stepper current to 600mA
TMC2130Z.stealthChop(1); // Enable extremely quiet stepping
TMC2130A = &TMC2130Z;
}
TMC2130A->begin(); // Initiate pins and registeries
TMC2130A->SilentStepStick2130(600); // Set stepper current to 600mA
TMC2130A->stealthChop(1); // Enable extremely quiet stepping
TMC2130A->shaft_dir(0);
TMC2130A->microsteps(0);
if (channelLabel == 'X')
{
TMC2130B->begin(); // Initiate pins and registeries
TMC2130B->SilentStepStick2130(600); // Set stepper current to 600mA
TMC2130B->stealthChop(1); // Enable extremely quiet stepping
TMC2130B->shaft_dir(0);
}
setMotorStepWrite = &StepperControlAxis::setMotorStepWriteTMC2130;
setMotorStepWrite2 = &StepperControlAxis::setMotorStepWriteTMC2130_2;
resetMotorStepWrite = &StepperControlAxis::resetMotorStepWriteTMC2130;
resetMotorStepWrite2 = &StepperControlAxis::resetMotorStepWriteTMC2130_2;
}
#endif
@ -336,9 +360,6 @@ void StepperControlAxis::incrementTick()
void StepperControlAxis::checkTiming()
{
//int i;
// moveTicks++;
if (stepIsOn)
{
if (moveTicks >= stepOffTick)
@ -347,7 +368,6 @@ void StepperControlAxis::checkTiming()
// Negative flank for the steps
resetMotorStep();
setTicks();
//stepOnTick = moveTicks + (500000.0 / motorInterruptSpeed / axisSpeed);
}
}
else
@ -359,7 +379,6 @@ void StepperControlAxis::checkTiming()
// Positive flank for the steps
setStepAxis();
//stepOffTick = moveTicks + (1000000.0 / motorInterruptSpeed / axisSpeed);
}
}
}
@ -586,51 +605,27 @@ void StepperControlAxis::setDirectionUp()
}
#endif
/**/
#if defined(FARMDUINO_EXP_V20)
if (channelLabel == 'X')
// The TMC2130 uses a command to change direction, not a pin
if (motorMotorInv)
{
if (motorMotorInv)
{
TMC2130X.shaft_dir(0);
}
else
{
TMC2130X.shaft_dir(1);
}
if (motorMotor2Enl && motorMotor2Inv)
{
TMC2130E.shaft_dir(0);
}
else
{
TMC2130E.shaft_dir(1);
}
TMC2130A->shaft_dir(0);
}
else
{
TMC2130A->shaft_dir(1);
}
if (channelLabel == 'Y')
if (motorMotor2Enl && motorMotor2Inv)
{
if (motorMotorInv)
{
TMC2130Y.shaft_dir(0);
}
else
{
TMC2130Y.shaft_dir(1);
}
TMC2130B->shaft_dir(0);
}
if (channelLabel == 'Z')
else
{
if (motorMotorInv)
{
TMC2130Z.shaft_dir(0);
}
else
{
TMC2130Z.shaft_dir(1);
}
TMC2130B->shaft_dir(1);
}
#endif
@ -639,6 +634,8 @@ void StepperControlAxis::setDirectionUp()
void StepperControlAxis::setDirectionDown()
{
#if !defined(FARMDUINO_EXP_V20)
if (motorMotorInv)
{
digitalWrite(pinDirection, HIGH);
@ -656,6 +653,34 @@ void StepperControlAxis::setDirectionDown()
{
digitalWrite(pin2Direction, LOW);
}
#endif
/**/
#if defined(FARMDUINO_EXP_V20)
// The TMC2130 uses a command to change direction, not a pin
if (motorMotorInv)
{
TMC2130A->shaft_dir(1);
}
else
{
TMC2130A->shaft_dir(0);
}
if (motorMotor2Enl && motorMotor2Inv)
{
TMC2130B->shaft_dir(1);
}
else
{
TMC2130B->shaft_dir(0);
}
#endif
}
void StepperControlAxis::setMovementUp()
@ -923,35 +948,39 @@ void StepperControlAxis::setMotorStepWriteTMC2130()
// so instead of setting the step bit,
// toggle the bit here
if (!tmcStep)
if (tmcStep)
{
digitalWrite(pinStep, HIGH);
}
tmcStep = false;
}
else
{
digitalWrite(pinStep, LOW);
tmcStep = true;
}
}
void StepperControlAxis::setMotorStepWriteTMC2130_2()
{
if (!tmcStep2)
if (tmcStep2)
{
digitalWrite(pin2Step, HIGH);
tmcStep2 = false;
}
else
{
digitalWrite(pin2Step, LOW);
tmcStep2 = true;
}
}
void StepperControlAxis::resetMotorStepWriteTMC2130()
{
// No action needed
}
void StepperControlAxis::resetMotorStepWriteTMC2130_2()
{
// No action needed
}
#endif

View File

@ -16,6 +16,16 @@
#include "Config.h"
#include <stdio.h>
#include <stdlib.h>
#include <TMC2130Stepper.h>
/*
#if defined(FARMDUINO_EXP_V20)
static TMC2130Stepper TMC2130X = TMC2130Stepper(X_ENABLE_PIN, X_DIR_PIN, X_STEP_PIN, X_CHIP_SELECT);
static TMC2130Stepper TMC2130Y = TMC2130Stepper(Y_ENABLE_PIN, Y_DIR_PIN, Y_STEP_PIN, Y_CHIP_SELECT);
static TMC2130Stepper TMC2130Z = TMC2130Stepper(Z_ENABLE_PIN, Z_DIR_PIN, Z_STEP_PIN, Z_CHIP_SELECT);
static TMC2130Stepper TMC2130E = TMC2130Stepper(E_ENABLE_PIN, E_DIR_PIN, E_STEP_PIN, E_CHIP_SELECT);
#endif
*/
class StepperControlAxis
{
@ -23,6 +33,9 @@ class StepperControlAxis
public:
StepperControlAxis();
TMC2130Stepper *TMC2130A;
TMC2130Stepper *TMC2130B;
void loadPinNumbers(int step, int dir, int enable, int min, int max, int step2, int dir2, int enable2);
void loadMotorSettings(long speedMax, long speedMin, long speedHome, long stepsAcc, long timeOut, bool homeIsUp, bool motorInv, bool endStInv, bool endStInv2, long interruptSpeed, bool motor2Enbl, bool motor2Inv, bool endStEnbl, bool stopAtHome, long maxSize, bool stopAtMax);
bool loadCoordinates(long sourcePoint, long destinationPoint, bool home);
@ -82,6 +95,17 @@ public:
void initTMC2130A();
#endif
/**/
#if defined(FARMDUINO_EXP_V20)
void setMotorStepWriteTMC2130();
void setMotorStepWriteTMC2130_2();
void resetMotorStepWriteTMC2130();
void resetMotorStepWriteTMC2130_2();
bool tmcStep = true;
bool tmcStep2 = true;
#endif
private:
int lastCalcLog = 0;
bool debugPrint = false;
@ -151,12 +175,12 @@ private:
unsigned long getLength(long l1, long l2);
void checkAxisDirection();
void (StepperControlAxis::*setMotorStepWrite)();
void (StepperControlAxis::*setMotorStepWrite2)();
void (StepperControlAxis::*resetMotorStepWrite)();
void (StepperControlAxis::*resetMotorStepWrite2)();
void setMotorStepWriteDefault();
void setMotorStepWriteDefault2();
void resetMotorStepWriteDefault();
@ -170,16 +194,6 @@ private:
void setMotorStepWrite46();
void resetMotorStepWrite46();
#if defined(FARMDUINO_EXP_V20)
void setMotorStepWriteTMC2130();
void setMotorStepWriteTMC2130_2();
void resetMotorStepWriteTMC2130();
void resetMotorStepWriteTMC2130_2();
bool tmcStep = true;
bool tmcStep2 = true;
#endif
};
#endif /* STEPPERCONTROLAXIS_H_ */

View File

@ -16,7 +16,7 @@
#include "TimerOne.h"
TimerOne Timer1; // preinstatiate
TimerOne Timer1; // preinstantiate
unsigned short TimerOne::pwmPeriod = 0;
unsigned char TimerOne::clockSelectBits = 0;

View File

@ -11,6 +11,18 @@
#include "CurrentState.h"
#include <SPI.h>
/*
#if defined(FARMDUINO_EXP_V20)
#include <TMC2130Stepper.h>
TMC2130Stepper TMC2130X = TMC2130Stepper(X_ENABLE_PIN, X_DIR_PIN, X_STEP_PIN, X_CHIP_SELECT);
TMC2130Stepper TMC2130Y = TMC2130Stepper(Y_ENABLE_PIN, Y_DIR_PIN, Y_STEP_PIN, Y_CHIP_SELECT);
TMC2130Stepper TMC2130Z = TMC2130Stepper(Z_ENABLE_PIN, Z_DIR_PIN, Z_STEP_PIN, Z_CHIP_SELECT);
TMC2130Stepper TMC2130E = TMC2130Stepper(E_ENABLE_PIN, E_DIR_PIN, E_STEP_PIN, E_CHIP_SELECT);
TMC2130Stepper *TMC2130A;
#endif
*/
//#include <TMC2130Stepper.h>
@ -72,32 +84,35 @@ void interrupt(void)
interruptBusy = true;
StepperControl::getInstance()->handleMovementInterrupt();
// Check the actions triggered once per second
//if (interruptSecondTimer >= 1000000 / MOVEMENT_INTERRUPT_SPEED)
//{
// interruptSecondTimer = 0;
// PinGuard::getInstance()->checkPins();
// //blinkLed();
//}
//interruptStopTime = micros();
//if (interruptStopTime > interruptStartTime)
//{
// interruptDuration = interruptStopTime - interruptStartTime;
//}
//if (interruptDuration > interruptDurationMax)
//{
// interruptDurationMax = interruptDuration;
//}
interruptBusy = false;
}
}
}
/**/
//bool blinky = false;
//int blinkyCounter = 0;
ISR(TIMER2_OVF_vect) {
//blinkyCounter++;
//if (blinkyCounter > 16000) {
// blinkyCounter = 0;
// blinky = !blinky;
//}
if (!debugInterrupt)
{
if (interruptBusy == false)
{
interruptBusy = true;
StepperControl::getInstance()->handleMovementInterrupt();
interruptBusy = false;
}
}
}
//The setup function is called once at startup of the sketch
void setup()
{
@ -265,7 +280,7 @@ void setup()
SPI.begin();
#endif
Serial.begin(115200);
delay(100);
@ -287,13 +302,32 @@ void setup()
// Interrupt management code library written by Paul Stoffregen
// The default time 100 micro seconds
/**/
#if !defined(FARMDUINO_EXP_V20)
Timer1.attachInterrupt(interrupt);
Timer1.initialize(MOVEMENT_INTERRUPT_SPEED);
Timer1.start();
#endif
#if defined(FARMDUINO_EXP_V20)
//const int MOVEMENT_INTERRUPT_SPEED = 64; // Interrupt cycle in micro seconds
//microseconds = 64
//const unsigned long cycles = (F_CPU / 2000000) * microseconds;
//const unsigned long cycles = (F_TIMER / 2000000) * microseconds;
//if (cycles < TIMER1_RESOLUTION)
//clockSelectBits = 1;
//pwmPeriod = cycles >> 1;
TIMSK2 = (TIMSK2 & B11111110) | 0x01; // Enable timer overflow
TCCR2B = (TCCR2B & B11111000) | 0x01; // Set divider to 1
OCR2A = 4; // Set overflow to 4 for total of 64 µs
pinMode(LED_PIN, OUTPUT);
#endif
// Initialize the inactivity check
lastAction = millis();
@ -340,7 +374,23 @@ void setup()
//digitalWrite(X_ENABLE_PIN, LOW);
//testingAxis.initTMC2130A();
//#if defined(FARMDUINO_EXP_V20)
/*
TMC2130A = &TMC2130X;
TMC2130A->begin(); // Initiate pins and registeries
TMC2130A->SilentStepStick2130(600); // Set stepper current to 600mA
TMC2130A->stealthChop(1); // Enable extremely quiet stepping
TMC2130A->shaft_dir(0);
*/
//TMC2130X.begin(); // Initiate pins and registeries
//TMC2130X.SilentStepStick2130(600); // Set stepper current to 600mA
//TMC2130X.stealthChop(1); // Enable extremely quiet stepping
//TMC2130X.shaft_dir(0);
StepperControl::getInstance()->initTMC2130A();
//#endif
}
@ -351,15 +401,25 @@ char commandChar[INCOMING_CMD_BUF_SIZE + 1];
void loop()
{
//digitalWrite(LED_PIN, blinky);
/**/
//StepperControl::getInstance()->test();
//digitalWrite(X_ENABLE_PIN, LOW);
//digitalWrite(X_STEP_PIN, stepperFlip);
//digitalWrite(X_STEP_PIN, HIGH);
//delayMicroseconds(10);
//digitalWrite(X_STEP_PIN, LOW);
//delayMicroseconds(10);
//#if defined(FARMDUINO_EXP_V20)
//StepperControl::getInstance()->test();
//delayMicroseconds(10);
//#endif
//digitalWrite(X_STEP_PIN, stepperFlip);
//delayMicroseconds(10);
//stepperFlip != stepperFlip;