corrections for new library
parent
09695d338a
commit
e8c97d9783
|
@ -247,17 +247,17 @@ void Movement::loadSettings()
|
|||
|
||||
/**/
|
||||
|
||||
motorCurrentX = 600;
|
||||
motorCurrentX = 300;
|
||||
stallSensitivityX = 0;
|
||||
microStepsX = 0;
|
||||
microStepsX = 8;
|
||||
|
||||
motorCurrentY = 600;
|
||||
motorCurrentY = 300;
|
||||
stallSensitivityY = 0;
|
||||
microStepsY = 0;
|
||||
microStepsY = 8;
|
||||
|
||||
motorCurrentZ = 600;
|
||||
motorCurrentZ = 300;
|
||||
stallSensitivityZ = 0;
|
||||
microStepsZ = 0;
|
||||
microStepsZ = 8;
|
||||
|
||||
axisX.loadSettingsTMC2130(motorCurrentX, stallSensitivityX, microStepsX);
|
||||
axisY.loadSettingsTMC2130(motorCurrentX, stallSensitivityX, microStepsX);
|
||||
|
|
|
@ -92,16 +92,16 @@ void MovementAxis::initTMC2130()
|
|||
|
||||
if (channelLabel == 'X')
|
||||
{
|
||||
TMC2130A = TMC2130X;
|
||||
TMC2130B = TMC2130E;
|
||||
TMC2130A = &TMC2130X;
|
||||
TMC2130B = &TMC2130E;
|
||||
}
|
||||
if (channelLabel == 'Y')
|
||||
{
|
||||
TMC2130A = TMC2130Y;
|
||||
TMC2130A = &TMC2130Y;
|
||||
}
|
||||
if (channelLabel == 'Z')
|
||||
{
|
||||
TMC2130A = TMC2130Z;
|
||||
TMC2130A = &TMC2130Z;
|
||||
}
|
||||
|
||||
setMotorStepWrite = &MovementAxis::setMotorStepWriteTMC2130;
|
||||
|
@ -120,11 +120,11 @@ void MovementAxis::initTMC2130()
|
|||
void MovementAxis::loadSettingsTMC2130(int motorCurrent, int stallSensitivity, int microSteps)
|
||||
{
|
||||
|
||||
loadTMC2130ParametersMotor(TMC2130A, microSteps, stallSensitivity, microSteps);
|
||||
loadTMC2130ParametersMotor(TMC2130A, microSteps, motorCurrent, stallSensitivity);
|
||||
|
||||
if (channelLabel == 'X')
|
||||
{
|
||||
loadTMC2130ParametersMotor(TMC2130B, microSteps, stallSensitivity, microSteps);
|
||||
loadTMC2130ParametersMotor(TMC2130B, microSteps, motorCurrent, stallSensitivity);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -9,12 +9,23 @@
|
|||
|
||||
void loadTMC2130ParametersMotor(Trinamic_TMC2130 *myStepper, int microsteps, int current, int sensitivity)
|
||||
{
|
||||
// stepper
|
||||
//myStepper->init();
|
||||
Serial.print("==>");
|
||||
Serial.print(" ");
|
||||
Serial.print(microsteps);
|
||||
Serial.print(" ");
|
||||
Serial.print(current);
|
||||
Serial.print(" ");
|
||||
Serial.print(sensitivity);
|
||||
Serial.println(" ");
|
||||
|
||||
/**/
|
||||
myStepper->init();
|
||||
|
||||
myStepper->set_mres(microsteps); // ({1,2,4,8,16,32,64,128,256}) number of microsteps
|
||||
//myStepper->set_IHOLD_IRUN(31, 31, 5); // ([0-31],[0-31],[0-5]) sets all currents to maximum
|
||||
myStepper->set_I_scale_analog(1); // ({0,1}) 0: I_REF internal, 1: sets I_REF to AIN
|
||||
|
||||
// load drive current for motors
|
||||
{
|
||||
uint16_t mA = current;
|
||||
float multiplier = 0.5;
|
||||
|
@ -30,6 +41,7 @@ void loadTMC2130ParametersMotor(Trinamic_TMC2130 *myStepper, int microsteps, int
|
|||
myStepper->set_toff(3); // ([0-15]) 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
|
||||
myStepper->set_tbl(1); // ([0-3]) set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
|
||||
|
||||
// load settings needed for enabling stall guard
|
||||
myStepper->set_diag1_stall(1);
|
||||
myStepper->set_diag1_onstate(1);
|
||||
myStepper->set_TCOOLTHRS(0xFFFFF);
|
||||
|
|
|
@ -13,15 +13,16 @@
|
|||
#include "Trinamic\Trinamic_TMC2130.h"
|
||||
#include "pins.h"
|
||||
|
||||
static Trinamic_TMC2130 *TMC2130X;
|
||||
static Trinamic_TMC2130 *TMC2130Y;
|
||||
static Trinamic_TMC2130 *TMC2130Z;
|
||||
static Trinamic_TMC2130 *TMC2130E;
|
||||
//static Trinamic_TMC2130 *TMC2130X;
|
||||
//static Trinamic_TMC2130 *TMC2130Y;
|
||||
//static Trinamic_TMC2130 *TMC2130Z;
|
||||
//static Trinamic_TMC2130 *TMC2130E;
|
||||
|
||||
//Trinamic_TMC2130 TMC2130X(X_CHIP_SELECT);
|
||||
//Trinamic_TMC2130 TMC2130Y(Y_CHIP_SELECT);
|
||||
//Trinamic_TMC2130 TMC2130Z(Z_CHIP_SELECT);
|
||||
//Trinamic_TMC2130 TMC2130E(E_CHIP_SELECT);
|
||||
|
||||
static Trinamic_TMC2130 TMC2130X(X_CHIP_SELECT);
|
||||
static Trinamic_TMC2130 TMC2130Y(Y_CHIP_SELECT);
|
||||
static Trinamic_TMC2130 TMC2130Z(Z_CHIP_SELECT);
|
||||
static Trinamic_TMC2130 TMC2130E(E_CHIP_SELECT);
|
||||
|
||||
void loadTMC2130ParametersMotor(Trinamic_TMC2130 *myStepper, int microsteps, int current, int sensitivity);
|
||||
|
||||
|
|
|
@ -302,39 +302,6 @@ void checkEncoders()
|
|||
|
||||
}
|
||||
|
||||
void runTestForDebug()
|
||||
{
|
||||
|
||||
//Serial.print("* ");
|
||||
//Serial.print(intrCounter / 1000);
|
||||
//Serial.print("\r\n");
|
||||
//delay(500);
|
||||
|
||||
//Serial.print("z");
|
||||
//blinkLed();
|
||||
//delay(500);
|
||||
|
||||
//Serial.print(millis());
|
||||
//Serial.print("X");
|
||||
//Serial.print("\r\n");
|
||||
//delay(1000);
|
||||
|
||||
//blinkLed();
|
||||
|
||||
//Movement::getInstance()->test();
|
||||
//delayMicroseconds(100);
|
||||
|
||||
//digitalWrite(LED_PIN, true);
|
||||
//delay(250);
|
||||
//digitalWrite(LED_PIN, false);
|
||||
//delay(250);
|
||||
|
||||
//if (debugInterrupt)
|
||||
//{
|
||||
// Movement::getInstance()->handleMovementInterrupt();
|
||||
//}
|
||||
}
|
||||
|
||||
// Set pins input output
|
||||
#ifdef RAMPS_V14
|
||||
void setPinInputOutput()
|
||||
|
@ -516,24 +483,52 @@ void setPinInputOutput()
|
|||
#if defined(FARMDUINO_EXP_V20)
|
||||
void setPinInputOutput()
|
||||
{
|
||||
Serial.print(COMM_REPORT_COMMENT);
|
||||
Serial.print(SPACE);
|
||||
Serial.print("Set input/output farmbot express");
|
||||
Serial.print(CRLF);
|
||||
|
||||
// Motor step, direction and pin is set up using the control chip library
|
||||
// This board also does not use encoders
|
||||
|
||||
pinMode(X_ENABLE_PIN, OUTPUT);
|
||||
pinMode(X_DIR_PIN, OUTPUT);
|
||||
pinMode(X_STEP_PIN, OUTPUT);
|
||||
pinMode(X_MIN_PIN, INPUT_PULLUP);
|
||||
pinMode(X_MAX_PIN, INPUT_PULLUP);
|
||||
|
||||
pinMode(E_ENABLE_PIN, OUTPUT);
|
||||
digitalWrite(X_ENABLE_PIN, HIGH);
|
||||
digitalWrite(X_DIR_PIN, LOW);
|
||||
digitalWrite(X_STEP_PIN, LOW);
|
||||
|
||||
pinMode(Y_ENABLE_PIN, OUTPUT);
|
||||
pinMode(Y_DIR_PIN, OUTPUT);
|
||||
pinMode(Y_STEP_PIN, OUTPUT);
|
||||
pinMode(Y_MIN_PIN, INPUT_PULLUP);
|
||||
pinMode(Y_MAX_PIN, INPUT_PULLUP);
|
||||
|
||||
digitalWrite(Y_ENABLE_PIN, HIGH);
|
||||
digitalWrite(Y_DIR_PIN, LOW);
|
||||
digitalWrite(Y_STEP_PIN, LOW);
|
||||
|
||||
pinMode(Z_ENABLE_PIN, OUTPUT);
|
||||
pinMode(Z_DIR_PIN, OUTPUT);
|
||||
pinMode(Z_STEP_PIN, OUTPUT);
|
||||
pinMode(Z_MIN_PIN, INPUT_PULLUP);
|
||||
pinMode(Z_MAX_PIN, INPUT_PULLUP);
|
||||
|
||||
digitalWrite(Z_ENABLE_PIN, HIGH);
|
||||
digitalWrite(Z_DIR_PIN, LOW);
|
||||
digitalWrite(Z_STEP_PIN, LOW);
|
||||
|
||||
pinMode(E_ENABLE_PIN, OUTPUT);
|
||||
pinMode(E_DIR_PIN, OUTPUT);
|
||||
pinMode(E_STEP_PIN, OUTPUT);
|
||||
|
||||
digitalWrite(E_ENABLE_PIN, HIGH);
|
||||
digitalWrite(E_DIR_PIN, LOW);
|
||||
digitalWrite(E_STEP_PIN, LOW);
|
||||
|
||||
pinMode(AUX_STEP_PIN, OUTPUT);
|
||||
pinMode(AUX_DIR_PIN, OUTPUT);
|
||||
pinMode(AUX_ENABLE_PIN, OUTPUT);
|
||||
|
@ -561,10 +556,6 @@ void setPinInputOutput()
|
|||
pinMode(SERVO_2_PIN, OUTPUT);
|
||||
pinMode(SERVO_3_PIN, OUTPUT);
|
||||
|
||||
Serial.print(COMM_REPORT_COMMENT);
|
||||
Serial.print(SPACE);
|
||||
Serial.print("Set input/output");
|
||||
Serial.print(CRLF);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -710,10 +701,10 @@ void startServo()
|
|||
#if defined(FARMDUINO_EXP_V20)
|
||||
|
||||
/**/
|
||||
//Trinamic_TMC2130 controllerTMC2130_X(X_CHIP_SELECT);
|
||||
//Trinamic_TMC2130 controllerTMC2130_Y(Y_CHIP_SELECT);
|
||||
//Trinamic_TMC2130 controllerTMC2130_Z(Z_CHIP_SELECT);
|
||||
//Trinamic_TMC2130 controllerTMC2130_E(E_CHIP_SELECT);
|
||||
//static Trinamic_TMC2130 controllerTMC2130_X(X_CHIP_SELECT);
|
||||
//static Trinamic_TMC2130 controllerTMC2130_Y(Y_CHIP_SELECT);
|
||||
//static Trinamic_TMC2130 controllerTMC2130_Z(Z_CHIP_SELECT);
|
||||
//static Trinamic_TMC2130 controllerTMC2130_E(E_CHIP_SELECT);
|
||||
|
||||
void loadTMC2130drivers()
|
||||
{
|
||||
|
@ -728,19 +719,25 @@ void loadTMC2130drivers()
|
|||
//TMC2130Z.init();
|
||||
//TMC2130E.init();
|
||||
|
||||
Trinamic_TMC2130 controllerTMC2130_X = Trinamic_TMC2130(X_CHIP_SELECT);
|
||||
Trinamic_TMC2130 controllerTMC2130_Y = Trinamic_TMC2130(Y_CHIP_SELECT);
|
||||
Trinamic_TMC2130 controllerTMC2130_Z = Trinamic_TMC2130(Z_CHIP_SELECT);
|
||||
Trinamic_TMC2130 controllerTMC2130_E = Trinamic_TMC2130(E_CHIP_SELECT);
|
||||
//Trinamic_TMC2130 controllerTMC2130_X = Trinamic_TMC2130(X_CHIP_SELECT);
|
||||
//Trinamic_TMC2130 controllerTMC2130_Y = Trinamic_TMC2130(Y_CHIP_SELECT);
|
||||
//Trinamic_TMC2130 controllerTMC2130_Z = Trinamic_TMC2130(Z_CHIP_SELECT);
|
||||
//Trinamic_TMC2130 controllerTMC2130_E = Trinamic_TMC2130(E_CHIP_SELECT);
|
||||
|
||||
TMC2130X = &controllerTMC2130_X;
|
||||
TMC2130Y = &controllerTMC2130_Y;
|
||||
TMC2130Z = &controllerTMC2130_Z;
|
||||
TMC2130E = &controllerTMC2130_E;
|
||||
//TMC2130X = &controllerTMC2130_X;
|
||||
//TMC2130Y = &controllerTMC2130_Y;
|
||||
//TMC2130Z = &controllerTMC2130_Z;
|
||||
//TMC2130E = &controllerTMC2130_E;
|
||||
}
|
||||
|
||||
void loadTMC2130parameters()
|
||||
{
|
||||
// Initialize the drivers
|
||||
Serial.print(COMM_REPORT_COMMENT);
|
||||
Serial.print(SPACE);
|
||||
Serial.print("Load TMC2130 parameters");
|
||||
Serial.print(CRLF);
|
||||
|
||||
Movement::getInstance()->loadSettingsTMC2130();
|
||||
}
|
||||
|
||||
|
@ -754,6 +751,15 @@ void startupTmc()
|
|||
Serial.print(CRLF);
|
||||
|
||||
Movement::getInstance()->initTMC2130();
|
||||
|
||||
//loadTMC2130parameters();
|
||||
|
||||
//TMC2130X.init();
|
||||
//TMC2130Y.init();
|
||||
//TMC2130Z.init();
|
||||
//TMC2130E.init();
|
||||
|
||||
//Movement::getInstance()->initTMC2130();
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -761,4 +767,114 @@ void initLastAction()
|
|||
{
|
||||
// Initialize the inactivity check
|
||||
lastAction = millis();
|
||||
}
|
||||
}
|
||||
|
||||
void setupTestForDebug()
|
||||
{
|
||||
|
||||
Serial.print(COMM_REPORT_COMMENT);
|
||||
Serial.print(SPACE);
|
||||
Serial.print("Setup Debug");
|
||||
Serial.print(CRLF);
|
||||
|
||||
digitalWrite(X_ENABLE_PIN, LOW);
|
||||
digitalWrite(Y_ENABLE_PIN, LOW);
|
||||
digitalWrite(Z_ENABLE_PIN, LOW);
|
||||
digitalWrite(E_ENABLE_PIN, LOW);
|
||||
|
||||
//digitalWrite(X_STEP_PIN, false);
|
||||
//digitalWrite(Y_STEP_PIN, false);
|
||||
//digitalWrite(Z_STEP_PIN, false);
|
||||
//digitalWrite(E_STEP_PIN, false);
|
||||
|
||||
//digitalWrite(X_DIR_PIN, false);
|
||||
//digitalWrite(Y_DIR_PIN, false);
|
||||
//digitalWrite(Z_DIR_PIN, false);
|
||||
//digitalWrite(E_DIR_PIN, false);
|
||||
|
||||
//digitalWrite(X_ENABLE_PIN, true);
|
||||
//digitalWrite(Y_ENABLE_PIN, true);
|
||||
//digitalWrite(Z_ENABLE_PIN, true);
|
||||
//digitalWrite(E_ENABLE_PIN, true);
|
||||
|
||||
//loadTMC2130ParametersMotor(&controllerTMC2130_X, 8, 500, 0); delay(100);
|
||||
//loadTMC2130ParametersMotor(&controllerTMC2130_Y, 8, 500, 0); delay(100);
|
||||
//loadTMC2130ParametersMotor(&controllerTMC2130_Z, 8, 500, 0); delay(100);
|
||||
//loadTMC2130ParametersMotor(&controllerTMC2130_E, 8, 500, 0); delay(100);
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
bool left = false;
|
||||
|
||||
void runTestForDebug()
|
||||
{
|
||||
|
||||
currentTime = millis();
|
||||
if (currentTime < lastAction)
|
||||
{
|
||||
|
||||
// If the device timer overruns, reset the idle counter
|
||||
lastAction = millis();
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
if ((currentTime - lastAction) > reportingPeriod)
|
||||
{
|
||||
blinkLed();
|
||||
Serial.print(".");
|
||||
lastAction = currentTime;
|
||||
|
||||
if (left) {
|
||||
left = false;
|
||||
digitalWrite(X_DIR_PIN, LOW);
|
||||
digitalWrite(Y_DIR_PIN, LOW);
|
||||
digitalWrite(Z_DIR_PIN, LOW);
|
||||
digitalWrite(E_DIR_PIN, LOW);
|
||||
}
|
||||
else {
|
||||
left = true;
|
||||
digitalWrite(X_DIR_PIN, HIGH);
|
||||
digitalWrite(Y_DIR_PIN, HIGH);
|
||||
digitalWrite(Z_DIR_PIN, HIGH);
|
||||
digitalWrite(E_DIR_PIN, HIGH);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
// make a step
|
||||
digitalWrite(X_STEP_PIN, HIGH);
|
||||
digitalWrite(Y_STEP_PIN, HIGH);
|
||||
digitalWrite(Z_STEP_PIN, HIGH);
|
||||
digitalWrite(E_STEP_PIN, HIGH);
|
||||
delayMicroseconds(100);
|
||||
|
||||
digitalWrite(X_STEP_PIN, LOW);
|
||||
digitalWrite(Y_STEP_PIN, LOW);
|
||||
digitalWrite(Z_STEP_PIN, LOW);
|
||||
digitalWrite(E_STEP_PIN, LOW);
|
||||
delayMicroseconds(100);
|
||||
|
||||
|
||||
|
||||
/*
|
||||
digitalWrite(X_STEP_PIN, HIGH);
|
||||
digitalWrite(E_STEP_PIN, HIGH);
|
||||
delayMicroseconds(100);
|
||||
|
||||
digitalWrite(X_STEP_PIN, LOW);
|
||||
digitalWrite(E_STEP_PIN, LOW);
|
||||
delayMicroseconds(100);
|
||||
*/
|
||||
|
||||
//Movement::getInstance()->test();
|
||||
//delayMicroseconds(100);
|
||||
|
||||
//if (debugInterrupt)
|
||||
//{
|
||||
// Movement::getInstance()->handleMovementInterrupt();
|
||||
//}
|
||||
}
|
||||
|
|
|
@ -61,6 +61,7 @@ void setup();
|
|||
void startServo();
|
||||
void startInterrupt();
|
||||
void homeOnBoot();
|
||||
void setupTestForDebug();
|
||||
void runTestForDebug();
|
||||
void checkEncoders();
|
||||
void checkPinGuard();
|
||||
|
|
175
src/src.ino
175
src/src.ino
|
@ -5,12 +5,17 @@
|
|||
*/
|
||||
|
||||
#include "farmbot_arduino_controller.h"
|
||||
//#include <SPI.h>
|
||||
//#include "Trinamic\Trinamic_TMC2130.h"
|
||||
//#include "pins.h"
|
||||
//#include "TMC2130.h"
|
||||
|
||||
// the setup function runs once when you press reset or power the board
|
||||
void setup()
|
||||
{
|
||||
setPinInputOutput();
|
||||
startSerial();
|
||||
setPinInputOutput();
|
||||
|
||||
readParameters();
|
||||
|
||||
#if defined(FARMDUINO_EXP_V20)
|
||||
|
@ -19,6 +24,10 @@ void setup()
|
|||
loadTMC2130parameters();
|
||||
#endif
|
||||
|
||||
//Serial.print("============");
|
||||
//Serial.print(CRLF);
|
||||
|
||||
|
||||
loadMovementSetting();
|
||||
startMotor();
|
||||
startPinGuard();
|
||||
|
@ -27,23 +36,163 @@ void setup()
|
|||
initLastAction();
|
||||
homeOnBoot();
|
||||
|
||||
Serial.print(COMM_REPORT_COMMENT);
|
||||
Serial.print(SPACE);
|
||||
Serial.print("ARDUINO STARTUP COMPLETE");
|
||||
Serial.print(CRLF);
|
||||
setupTestForDebug();
|
||||
|
||||
//Serial.print(COMM_REPORT_COMMENT);
|
||||
//Serial.print(SPACE);
|
||||
//Serial.print("ARDUINO STARTUP COMPLETE");
|
||||
//Serial.print(CRLF);
|
||||
|
||||
/*
|
||||
Serial.begin(115200); //init serial port and set baudrate
|
||||
while (!Serial); //wait for serial port to connect (needed for Leonardo only)
|
||||
Serial.println("Start...");
|
||||
*/
|
||||
|
||||
/*
|
||||
// pins
|
||||
pinMode(X_ENABLE_PIN, OUTPUT);
|
||||
pinMode(X_DIR_PIN, OUTPUT);
|
||||
pinMode(X_STEP_PIN, OUTPUT);
|
||||
digitalWrite(X_ENABLE_PIN, HIGH); // disable driver
|
||||
digitalWrite(X_DIR_PIN, LOW); // chose direction
|
||||
digitalWrite(X_STEP_PIN, LOW); // no step yet
|
||||
|
||||
pinMode(Y_ENABLE_PIN, OUTPUT);
|
||||
pinMode(Y_DIR_PIN, OUTPUT);
|
||||
pinMode(Y_STEP_PIN, OUTPUT);
|
||||
digitalWrite(Y_ENABLE_PIN, HIGH); // disable driver
|
||||
digitalWrite(Y_DIR_PIN, LOW); // chose direction
|
||||
digitalWrite(Y_STEP_PIN, LOW); // no step yet
|
||||
|
||||
pinMode(Z_ENABLE_PIN, OUTPUT);
|
||||
pinMode(Z_DIR_PIN, OUTPUT);
|
||||
pinMode(Z_STEP_PIN, OUTPUT);
|
||||
digitalWrite(Z_ENABLE_PIN, HIGH); // disable driver
|
||||
digitalWrite(Z_DIR_PIN, LOW); // chose direction
|
||||
digitalWrite(Z_STEP_PIN, LOW); // no step yet
|
||||
|
||||
pinMode(E_ENABLE_PIN, OUTPUT);
|
||||
pinMode(E_DIR_PIN, OUTPUT);
|
||||
pinMode(E_STEP_PIN, OUTPUT);
|
||||
digitalWrite(E_ENABLE_PIN, HIGH); // disable driver
|
||||
digitalWrite(E_DIR_PIN, LOW); // chose direction
|
||||
digitalWrite(E_STEP_PIN, LOW); // no step yet
|
||||
*/
|
||||
|
||||
/*
|
||||
Serial.println("Init");
|
||||
|
||||
loadTMC2130ParametersMotor(&TMC2130X, 8, 200, 0);
|
||||
loadTMC2130ParametersMotor(&TMC2130Y, 8, 200, 0);
|
||||
loadTMC2130ParametersMotor(&TMC2130Z, 8, 200, 0);
|
||||
loadTMC2130ParametersMotor(&TMC2130E, 8, 200, 0);
|
||||
*/
|
||||
|
||||
/*
|
||||
pinMode(X_ENABLE_PIN, OUTPUT);
|
||||
pinMode(X_DIR_PIN, OUTPUT);
|
||||
pinMode(X_STEP_PIN, OUTPUT);
|
||||
digitalWrite(X_ENABLE_PIN, HIGH); // disable driver
|
||||
digitalWrite(X_DIR_PIN, LOW); // chose direction
|
||||
digitalWrite(X_STEP_PIN, LOW); // no step yet
|
||||
|
||||
pinMode(Y_ENABLE_PIN, OUTPUT);
|
||||
pinMode(Y_DIR_PIN, OUTPUT);
|
||||
pinMode(Y_STEP_PIN, OUTPUT);
|
||||
digitalWrite(Y_ENABLE_PIN, HIGH); // disable driver
|
||||
digitalWrite(Y_DIR_PIN, LOW); // chose direction
|
||||
digitalWrite(Y_STEP_PIN, LOW); // no step yet
|
||||
|
||||
pinMode(Z_ENABLE_PIN, OUTPUT);
|
||||
pinMode(Z_DIR_PIN, OUTPUT);
|
||||
pinMode(Z_STEP_PIN, OUTPUT);
|
||||
digitalWrite(Z_ENABLE_PIN, HIGH); // disable driver
|
||||
digitalWrite(Z_DIR_PIN, LOW); // chose direction
|
||||
digitalWrite(Z_STEP_PIN, LOW); // no step yet
|
||||
|
||||
pinMode(E_ENABLE_PIN, OUTPUT);
|
||||
pinMode(E_DIR_PIN, OUTPUT);
|
||||
pinMode(E_STEP_PIN, OUTPUT);
|
||||
digitalWrite(E_ENABLE_PIN, HIGH); // disable driver
|
||||
digitalWrite(E_DIR_PIN, LOW); // chose direction
|
||||
digitalWrite(E_STEP_PIN, LOW); // no step yet
|
||||
*/
|
||||
|
||||
//loadTMC2130drivers();
|
||||
//startupTmc();
|
||||
//loadTMC2130parameters();
|
||||
|
||||
/**/
|
||||
//Movement::getInstance()->initTMC2130();
|
||||
//loadTMC2130parameters();
|
||||
|
||||
//loadTMC2130ParametersMotor(&TMC2130X, 8, 200, 0);
|
||||
//loadTMC2130ParametersMotor(&TMC2130Y, 8, 200, 0);
|
||||
//loadTMC2130ParametersMotor(&TMC2130Z, 8, 200, 0);
|
||||
//loadTMC2130ParametersMotor(&TMC2130E, 8, 200, 0);
|
||||
|
||||
|
||||
Serial.println("Enable pins");
|
||||
|
||||
digitalWrite(X_ENABLE_PIN, LOW); // enable driver
|
||||
digitalWrite(Y_ENABLE_PIN, LOW); // enable driver
|
||||
digitalWrite(Z_ENABLE_PIN, LOW); // enable driver
|
||||
digitalWrite(E_ENABLE_PIN, LOW); // enable driver
|
||||
|
||||
//Serial.println("Enable");
|
||||
|
||||
}
|
||||
|
||||
// the loop function runs over and over again until power down or reset
|
||||
void loop()
|
||||
{
|
||||
//runTestForDebug();
|
||||
runTestForDebug();
|
||||
|
||||
checkEncoders();
|
||||
checkPinGuard();
|
||||
checkSerialInputs();
|
||||
checkEmergencyStop();
|
||||
checkParamsChanged();
|
||||
periodicChecksAndReport();
|
||||
//checkEncoders();
|
||||
//checkPinGuard();
|
||||
//checkSerialInputs();
|
||||
//checkEmergencyStop();
|
||||
//checkParamsChanged();
|
||||
//periodicChecksAndReport();
|
||||
|
||||
}
|
||||
//static uint32_t last_time = 0;
|
||||
//uint32_t ms = millis();
|
||||
|
||||
/*
|
||||
// make a step
|
||||
digitalWrite(X_STEP_PIN, HIGH);
|
||||
digitalWrite(Y_STEP_PIN, HIGH);
|
||||
digitalWrite(Z_STEP_PIN, HIGH);
|
||||
digitalWrite(E_STEP_PIN, HIGH);
|
||||
delayMicroseconds(100);
|
||||
|
||||
digitalWrite(X_STEP_PIN, LOW);
|
||||
digitalWrite(Y_STEP_PIN, LOW);
|
||||
digitalWrite(Z_STEP_PIN, LOW);
|
||||
digitalWrite(E_STEP_PIN, LOW);
|
||||
delayMicroseconds(100);
|
||||
*/
|
||||
|
||||
/*
|
||||
TMC2130X.read_STAT();
|
||||
if (TMC2130X.isStandstill() || TMC2130X.isStallguard()) {
|
||||
Serial.print("X");
|
||||
}
|
||||
|
||||
TMC2130Y.read_STAT();
|
||||
if (TMC2130Y.isStandstill() || TMC2130Y.isStallguard()) {
|
||||
Serial.print("Y");
|
||||
}
|
||||
|
||||
TMC2130Z.read_STAT();
|
||||
if (TMC2130Z.isStandstill() || TMC2130Z.isStallguard()) {
|
||||
Serial.print("Z");
|
||||
}
|
||||
|
||||
TMC2130E.read_STAT();
|
||||
if (TMC2130E.isStandstill() || TMC2130E.isStallguard()) {
|
||||
Serial.print("E");
|
||||
}
|
||||
*/
|
||||
}
|
Loading…
Reference in New Issue