Configuration parameters for TMC2130 added

pull/118/head
Tim Evers 2019-04-27 22:56:53 +02:00
parent 7b668b4a7f
commit e500994615
8 changed files with 125 additions and 114 deletions

View File

@ -151,6 +151,11 @@
const long MOVEMENT_STALL_SENSITIVITY_Y_DEFAULT = 30;
const long MOVEMENT_STALL_SENSITIVITY_Z_DEFAULT = 30;
// micro steps setting (used with TMC2130)
const long MOVEMENT_MICROSTEPS_X_DEFAULT = 0;
const long MOVEMENT_MICROSTEPS_Y_DEFAULT = 0;
const long MOVEMENT_MICROSTEPS_Z_DEFAULT = 0;
// Use encoder (0 or 1)
const long ENCODER_ENABLED_X_DEFAULT = 0;
const long ENCODER_ENABLED_Y_DEFAULT = 0;

View File

@ -459,6 +459,16 @@ void ParameterList::loadDefaultValue(int id)
paramValues[id] = MOVEMENT_STALL_SENSITIVITY_Z_DEFAULT;
break;
case MOVEMENT_MICROSTEPS_X:
paramValues[id] = MOVEMENT_MICROSTEPS_X_DEFAULT;
break;
case MOVEMENT_MICROSTEPS_Y:
paramValues[id] = MOVEMENT_MICROSTEPS_Y_DEFAULT;
break;
case MOVEMENT_MICROSTEPS_Z:
paramValues[id] = MOVEMENT_MICROSTEPS_Z_DEFAULT;
break;
case ENCODER_ENABLED_X:
paramValues[id] = ENCODER_ENABLED_X_DEFAULT;
break;
@ -643,6 +653,9 @@ bool ParameterList::validParam(int id)
case MOVEMENT_STALL_SENSITIVITY_X:
case MOVEMENT_STALL_SENSITIVITY_Y:
case MOVEMENT_STALL_SENSITIVITY_Z:
case MOVEMENT_MICROSTEPS_X:
case MOVEMENT_MICROSTEPS_Y:
case MOVEMENT_MICROSTEPS_Z:
case ENCODER_ENABLED_X:
case ENCODER_ENABLED_Y:
case ENCODER_ENABLED_Z:

View File

@ -91,6 +91,11 @@ enum ParamListEnum
MOVEMENT_STALL_SENSITIVITY_Y = 86,
MOVEMENT_STALL_SENSITIVITY_Z = 87,
// microstepping (used with TMC2130)
MOVEMENT_MICROSTEPS_X = 88,
MOVEMENT_MICROSTEPS_Y = 89,
MOVEMENT_MICROSTEPS_Z = 90,
// encoder settings
ENCODER_ENABLED_X = 101,
ENCODER_ENABLED_Y = 102,

View File

@ -177,23 +177,35 @@ void StepperControl::loadSettings()
#if defined(FARMDUINO_EXP_V20)
void StepperControl::initTMC2130()
{
axisX.initTMC2130();
axisY.initTMC2130();
axisZ.initTMC2130();
}
void StepperControl::loadSettingsTMC2130()
{
/**/
int motorCurrent;
int stallSensitivity;
motorCurrent = ParameterList::getInstance()->getValue(MOVEMENT_MOTOR_CURRENT_X);
stallSensitivity = ParameterList::getInstance()->getValue(MOVEMENT_STALL_SENSITIVITY_X);
axisX.initTMC2130(motorCurrent, stallSensitivity);
int microSteps;
motorCurrent = ParameterList::getInstance()->getValue(MOVEMENT_MOTOR_CURRENT_X);
stallSensitivity = ParameterList::getInstance()->getValue(MOVEMENT_STALL_SENSITIVITY_X);
axisY.initTMC2130(motorCurrent, stallSensitivity);
microSteps = ParameterList::getInstance()->getValue(MOVEMENT_MICROSTEPS_X);
axisX.loadSettingsTMC2130(motorCurrent, stallSensitivity, microSteps);
motorCurrent = ParameterList::getInstance()->getValue(MOVEMENT_MOTOR_CURRENT_X);
stallSensitivity = ParameterList::getInstance()->getValue(MOVEMENT_STALL_SENSITIVITY_X);
axisZ.initTMC2130(motorCurrent, stallSensitivity);
motorCurrent = ParameterList::getInstance()->getValue(MOVEMENT_MOTOR_CURRENT_Y);
stallSensitivity = ParameterList::getInstance()->getValue(MOVEMENT_STALL_SENSITIVITY_Y);
microSteps = ParameterList::getInstance()->getValue(MOVEMENT_MICROSTEPS_Y);
axisY.loadSettingsTMC2130(motorCurrent, stallSensitivity, microSteps);
motorCurrent = ParameterList::getInstance()->getValue(MOVEMENT_MOTOR_CURRENT_Z);
stallSensitivity = ParameterList::getInstance()->getValue(MOVEMENT_STALL_SENSITIVITY_Z);
microSteps = ParameterList::getInstance()->getValue(MOVEMENT_MICROSTEPS_Z);
axisZ.loadSettingsTMC2130(motorCurrent, stallSensitivity, microSteps);
}
#endif
void StepperControl::test()
@ -422,19 +434,6 @@ int StepperControl::moveToCoords(double xDestScaled, double yDestScaled, double
// Let the interrupt handle all the movements
while ((axisActive[0] || axisActive[1] || axisActive[2]) && !emergencyStop)
{
/**/ //axisX.setMotorStep();
/**/ //delayMicroseconds(10);
//!@#$
//#if defined(FARMDUINO_EXP_V20)
//axisX.incrementTick();
//axisY.incrementTick();
//axisZ.incrementTick();
//#endif
/**/ //axisX.test();
/**/ axisX.getLostSteps();
#if defined(FARMDUINO_V14)
checkEncoders();
#endif
@ -674,14 +673,39 @@ int StepperControl::moveToCoords(double xDestScaled, double yDestScaled, double
case 1:
serialBuffer += CurrentState::getInstance()->getPosition();
serialBuffer += CurrentState::getInstance()->getQAndNewLine();
break;
case 2:
#if defined(FARMDUINO_EXP_V20)
serialBuffer += "R89";
serialBuffer += " X";
serialBuffer += axisX.getLoad();
serialBuffer += " Y";
serialBuffer += axisY.getLoad();
serialBuffer += " Z";
serialBuffer += axisZ.getLoad();
serialBuffer += CurrentState::getInstance()->getQAndNewLine();
#endif
break;
}
serialMessageNr++;
#if !defined(FARMDUINO_EXP_V20)
if (serialMessageNr > 1)
{
serialMessageNr = 0;
}
#endif
#if defined(FARMDUINO_EXP_V20)
if (serialMessageNr > 2)
{
serialMessageNr = 0;
}
#endif
serialBufferSending = 0;
@ -1282,20 +1306,22 @@ void StepperControl::checkAxisVsEncoder(StepperControlAxis *axis, StepperControl
#if defined(FARMDUINO_EXP_V20)
if (axis->stallDetected()) {
// In case of stall detection, count this as a missed step
(*missedSteps)++;
axis->setCurrentPosition(*lastPosition);
}
else {
// Decrease amount of missed steps if there are no missed step
if (*missedSteps > 0)
{
(*missedSteps) -= (*encoderStepDecay);
//if (*encoderEnabled) {
if (axis->stallDetected()) {
// In case of stall detection, count this as a missed step
(*missedSteps)++;
axis->setCurrentPosition(*lastPosition);
}
*lastPosition = axis->currentPosition();
}
else {
// Decrease amount of missed steps if there are no missed step
if (*missedSteps > 0)
{
(*missedSteps) -= (*encoderStepDecay);
}
*lastPosition = axis->currentPosition();
encoder->setPosition(axis->currentPosition());
}
// }
#endif
}
@ -1394,6 +1420,10 @@ void StepperControl::loadMotorSettings()
axisY.loadMotorSettings(speedMax[1], speedMin[1], speedHome[1], stepsAcc[1], timeOut[1], homeIsUp[1], motorInv[1], endStInv[1], endStInv2[1], MOVEMENT_INTERRUPT_SPEED, motor2Enbl[1], motor2Inv[1], endStEnbl[1], motorStopAtHome[1], motorMaxSize[1] *= stepsPerMm[1], motorStopAtMax[1]);
axisZ.loadMotorSettings(speedMax[2], speedMin[2], speedHome[2], stepsAcc[2], timeOut[2], homeIsUp[2], motorInv[2], endStInv[2], endStInv2[2], MOVEMENT_INTERRUPT_SPEED, motor2Enbl[2], motor2Inv[2], endStEnbl[2], motorStopAtHome[2], motorMaxSize[2] *= stepsPerMm[2], motorStopAtMax[2]);
#if defined(FARMDUINO_EXP_V20)
loadSettingsTMC2130();
#endif
primeMotors();
}
@ -1712,4 +1742,4 @@ void StepperControl::checkEncoders()
//encoderY.processEncoder();
//encoderZ.processEncoder();
}
}

View File

@ -39,6 +39,7 @@ public:
#if defined(FARMDUINO_EXP_V20)
void initTMC2130();
void loadSettingsTMC2130();
#endif

View File

@ -63,29 +63,11 @@ StepperControlAxis::StepperControlAxis()
unsigned int StepperControlAxis::getLostSteps()
{
unsigned int lostSteps;
lostSteps = TMC2130A->LOST_STEPS();
if (lostSteps != 0)
{
Serial.print("R99");
Serial.print(" mis stp = ");
Serial.print(lostSteps);
Serial.print("\r\n");
}
return lostSteps;
//return TMC2130A->LOST_STEPS();
return TMC2130A->LOST_STEPS();
}
void StepperControlAxis::test()
{
Serial.print("R99");
Serial.print(" mis stp = ");
Serial.print(TMC2130A->LOST_STEPS());
Serial.print("\r\n");
//setMotorStep();
//setMotorStepWriteTMC2130();
//Serial.print("R99");
@ -100,7 +82,7 @@ void StepperControlAxis::test()
}
#if defined(FARMDUINO_EXP_V20)
void StepperControlAxis::initTMC2130(int motorCurrent, int stallSensitivity)
void StepperControlAxis::initTMC2130()
{
/*
TMC2130X.begin(); // Initiate pins and registeries
@ -126,34 +108,13 @@ void StepperControlAxis::initTMC2130(int motorCurrent, int stallSensitivity)
TMC2130A->begin(); // Initiate pins and registeries
TMC2130A->rms_current(motorCurrent); // Set the required current in mA
TMC2130A->microsteps(0); // Minimum of micro steps needed
TMC2130A->chm(true); // Set the chopper mode to classic const. off time
TMC2130A->diag1_stall(1); // Activate stall diagnostics
TMC2130A->sgt(stallSensitivity); // Set stall detection sensitivity. most -64 to +64 least
TMC2130A->shaft_dir(0); // Set direction
//TMC2130A->SilentStepStick2130(600); // Set stepper current to 600mA
//TMC2130A->stealthChop(1); // Enable extremely quiet stepping
//TMC2130A->microsteps(0);
if (channelLabel == 'X')
{
TMC2130B->begin(); // Initiate pins and registeries
TMC2130B->rms_current(motorCurrent); // Set the required current in mA
TMC2130B->microsteps(0); // Minimum of micro steps needed
TMC2130B->chm(true); // Set the chopper mode to classic const. off time
TMC2130B->diag1_stall(1); // Activate stall diagnostics
TMC2130B->sgt(stallSensitivity); // Set stall detection sensitivity. most -64 to +64 least
TMC2130B->shaft_dir(0); // Set direction
//TMC2130B->SilentStepStick2130(600); // Set stepper current to 600mA
//TMC2130B->stealthChop(1); // Enable extremely quiet stepping
//TMC2130B->shaft_dir(0);
}
//loadSettingsTMC2130(600,60, 0);
setMotorStepWrite = &StepperControlAxis::setMotorStepWriteTMC2130;
setMotorStepWrite2 = &StepperControlAxis::setMotorStepWriteTMC2130_2;
resetMotorStepWrite = &StepperControlAxis::resetMotorStepWriteTMC2130;
@ -161,10 +122,36 @@ void StepperControlAxis::initTMC2130(int motorCurrent, int stallSensitivity)
}
void StepperControlAxis::loadSettingsTMC2130(int motorCurrent, int stallSensitivity, int microSteps)
{
stallSensitivity = 60;
TMC2130A->rms_current(motorCurrent); // Set the required current in mA
TMC2130A->microsteps(microSteps); // Minimum of micro steps needed
TMC2130A->chm(true); // Set the chopper mode to classic const. off time
TMC2130A->diag1_stall(1); // Activate stall diagnostics
TMC2130A->sgt(stallSensitivity); // Set stall detection sensitivity. most -64 to +64 least
TMC2130A->shaft_dir(0); // Set direction
if (channelLabel == 'X')
{
TMC2130B->rms_current(motorCurrent); // Set the required current in mA
TMC2130B->microsteps(microSteps); // Minimum of micro steps needed
TMC2130B->chm(true); // Set the chopper mode to classic const. off time
TMC2130B->diag1_stall(1); // Activate stall diagnostics
TMC2130B->sgt(stallSensitivity); // Set stall detection sensitivity. most -64 to +64 least
TMC2130B->shaft_dir(0); // Set direction
}
}
bool StepperControlAxis::stallDetected() {
return TMC2130A->stallguard();
}
uint16_t StepperControlAxis::getLoad() {
return TMC2130A->sg_result();
}
#endif
unsigned int StepperControlAxis::calculateSpeed(long sourcePosition, long currentPosition, long destinationPosition, long minSpeed, long maxSpeed, long stepsAccDec)

View File

@ -92,8 +92,10 @@ public:
bool movementStarted;
#if defined(FARMDUINO_EXP_V20)
void initTMC2130(int motorCurrent, int stallSensitivity);
void initTMC2130();
void loadSettingsTMC2130(int motorCurrent, int stallSensitivity, int microSteps);
bool stallDetected();
uint16_t getLoad();
#endif
/**/

View File

@ -310,22 +310,10 @@ void setup()
#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
@ -367,31 +355,11 @@ void setup()
Serial.print("R99 ARDUINO STARTUP COMPLETE\r\n");
/**/
//stepper.begin();
//stepper.SilentStepStick2130(600);
//stepper.stealthChop(1);
//stepper.shaft_dir(0);
//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);
#if defined(FARMDUINO_EXP_V20)
// initialise the motors
StepperControl::getInstance()->initTMC2130();
//#endif
StepperControl::getInstance()->loadSettingsTMC2130();
#endif
}