Merge pull request #123 from TimEvWw/master

TMC2130 modifications
pull/124/head
Tim Evers 2020-01-22 22:09:29 +01:00 committed by GitHub
commit 96ee6279a7
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
27 changed files with 999 additions and 2124 deletions

View File

@ -1,9 +1,9 @@
#ifndef FARMBOT_BOARD_ID
#define RAMPS_V14
//#define RAMPS_V14
//#define FARMDUINO_V10
//#define FARMDUINO_V14
//#define FARMDUINO_EXP_V20
#define FARMDUINO_EXP_V20
#else

View File

@ -234,94 +234,26 @@ void Movement::loadSettings()
motorCurrentX = ParameterList::getInstance()->getValue(MOVEMENT_MOTOR_CURRENT_X);
stallSensitivityX = ParameterList::getInstance()->getValue(MOVEMENT_STALL_SENSITIVITY_X);
microStepsX = ParameterList::getInstance()->getValue(MOVEMENT_MICROSTEPS_X);
//axisX.loadSettingsTMC2130(motorCurrent, stallSensitivity, microSteps);
motorCurrentY = ParameterList::getInstance()->getValue(MOVEMENT_MOTOR_CURRENT_Y);
stallSensitivityY = ParameterList::getInstance()->getValue(MOVEMENT_STALL_SENSITIVITY_Y);
microStepsY = ParameterList::getInstance()->getValue(MOVEMENT_MICROSTEPS_Y);
//axisY.loadSettingsTMC2130(motorCurrent, stallSensitivity, microSteps);
motorCurrentZ = ParameterList::getInstance()->getValue(MOVEMENT_MOTOR_CURRENT_Z);
stallSensitivityZ = ParameterList::getInstance()->getValue(MOVEMENT_STALL_SENSITIVITY_Z);
microStepsX = ParameterList::getInstance()->getValue(MOVEMENT_MICROSTEPS_Z);
//axisZ.loadSettingsTMC2130(motorCurrent, stallSensitivity, microSteps);
motorCurrentX = 600;
stallSensitivityX = 0;
microStepsX = 0;
motorCurrentY = 600;
stallSensitivityX = 0;
stallSensitivityY = 0;
microStepsY = 0;
motorCurrentZ = 600;
stallSensitivityZ = 0;
microStepsZ = 0;
TMC2130X->push();
TMC2130X->toff(3);
TMC2130X->tbl(1);
TMC2130X->hysteresis_start(4);
TMC2130X->hysteresis_end(-2);
TMC2130X->rms_current(motorCurrentX); // mA
TMC2130X->microsteps(microStepsX);
TMC2130X->diag1_stall(1);
TMC2130X->diag1_active_high(1);
TMC2130X->coolstep_min_speed(0xFFFFF); // 20bit max
TMC2130X->THIGH(0);
TMC2130X->semin(5);
TMC2130X->semax(2);
TMC2130X->sedn(0b01);
TMC2130X->sg_stall_value(stallSensitivityX);
TMC2130Y->push();
TMC2130Y->toff(3);
TMC2130Y->tbl(1);
TMC2130Y->hysteresis_start(4);
TMC2130Y->hysteresis_end(-2);
TMC2130Y->rms_current(motorCurrentY); // mA
TMC2130Y->microsteps(microStepsY);
TMC2130Y->diag1_stall(1);
TMC2130Y->diag1_active_high(1);
TMC2130Y->coolstep_min_speed(0xFFFFF); // 20bit max
TMC2130Y->THIGH(0);
TMC2130Y->semin(5);
TMC2130Y->semax(2);
TMC2130Y->sedn(0b01);
TMC2130Y->sg_stall_value(stallSensitivityY);
TMC2130Z->push();
TMC2130Z->toff(3);
TMC2130Z->tbl(1);
TMC2130Z->hysteresis_start(4);
TMC2130Z->hysteresis_end(-2);
TMC2130Z->rms_current(motorCurrentZ); // mA
TMC2130Z->microsteps(microStepsZ);
TMC2130Z->diag1_stall(1);
TMC2130Z->diag1_active_high(1);
TMC2130Z->coolstep_min_speed(0xFFFFF); // 20bit max
TMC2130Z->THIGH(0);
TMC2130Z->semin(5);
TMC2130Z->semax(2);
TMC2130Z->sedn(0b01);
TMC2130Z->sg_stall_value(stallSensitivityZ);
TMC2130E->push();
TMC2130E->toff(3);
TMC2130E->tbl(1);
TMC2130E->hysteresis_start(4);
TMC2130E->hysteresis_end(-2);
TMC2130E->rms_current(600); // mA
TMC2130E->microsteps(0);
TMC2130E->diag1_stall(1);
TMC2130E->diag1_active_high(1);
TMC2130E->coolstep_min_speed(0xFFFFF); // 20bit max
TMC2130E->THIGH(0);
TMC2130E->semin(5);
TMC2130E->semax(2);
TMC2130E->sedn(0b01);
TMC2130E->sg_stall_value(0);
if (microStepsX <= 0) { microStepsX = 1; }
if (microStepsY <= 0) { microStepsY = 1; }
if (microStepsZ <= 0) { microStepsZ = 1; }
axisX.loadSettingsTMC2130(motorCurrentX, stallSensitivityX, microStepsX);
axisY.loadSettingsTMC2130(motorCurrentX, stallSensitivityX, microStepsX);
axisZ.loadSettingsTMC2130(motorCurrentX, stallSensitivityX, microStepsX);
}
#endif
@ -1373,9 +1305,9 @@ int Movement::calibrateAxis(int axis)
int debugPrintCount = 0;
// Check encoder to verify the motor is at the right position
#if !defined(FARMDUINO_EXP_V20)
void Movement::checkAxisVsEncoder(MovementAxis *axis, MovementEncoder *encoder, float *missedSteps, long *lastPosition, long *encoderLastPosition, int *encoderUseForPos, float *encoderStepDecay, bool *encoderEnabled)
{
#if !defined(FARMDUINO_EXP_V20)
if (*encoderEnabled)
{
bool stepMissed = false;
@ -1441,47 +1373,50 @@ void Movement::checkAxisVsEncoder(MovementAxis *axis, MovementEncoder *encoder,
axis->setCurrentPosition(encoder->currentPosition());
}
}
}
#endif
//#if defined(FARMDUINO_EXP_V20)
//
// /**/
// /*
// Serial.print("R99");
// Serial.print(" XXX ");
// Serial.print(" cur pos ");
// Serial.print(axis->currentPosition());
// Serial.print(" last pos ");
// Serial.print(*lastPosition);
// */
//
// if (*encoderEnabled) {
// 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);
// }
// *lastPosition = axis->currentPosition();
// encoder->setPosition(axis->currentPosition());
// }
// }
//
// //Serial.print(" new last pos ");
// //Serial.print(*lastPosition);
// //Serial.print(" en pos ");
// //Serial.print(encoder->currentPosition());
// //Serial.print("\r\n");
//
//
//#endif
#if defined(FARMDUINO_EXP_V20)
void Movement::checkAxisVsEncoder(MovementAxis *axis, MovementEncoder *encoder, float *missedSteps, long *lastPosition, long *encoderLastPosition, int *encoderUseForPos, float *encoderStepDecay, bool *encoderEnabled)
{
//
// /**/
// /*
// Serial.print("R99");
// Serial.print(" XXX ");
// Serial.print(" cur pos ");
// Serial.print(axis->currentPosition());
// Serial.print(" last pos ");
// Serial.print(*lastPosition);
// */
//
// if (*encoderEnabled) {
// 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);
// }
// *lastPosition = axis->currentPosition();
// encoder->setPosition(axis->currentPosition());
// }
// }
//
// //Serial.print(" new last pos ");
// //Serial.print(*lastPosition);
// //Serial.print(" en pos ");
// //Serial.print(encoder->currentPosition());
// //Serial.print("\r\n");
//
//
}
#endif
void Movement::loadMotorSettings()
{

View File

@ -7,15 +7,6 @@
#include "MovementAxis.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
*/
MovementAxis::MovementAxis()
{
lastCalcLog = 0;
@ -84,7 +75,9 @@ void MovementAxis::test()
unsigned int MovementAxis::getLostSteps()
{
return TMC2130A->LOST_STEPS();
/**/
//return TMC2130A->get_MSCNT();
return 0;
}
void MovementAxis::initTMC2130()
@ -92,25 +85,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->begin(); // Initiate pins and registeries
//TMC2130A->shaft_dir(0); // Set direction
if (channelLabel == 'X')
{
//TMC2130B->begin(); // Initiate pins and registeries
//TMC2130B->shaft_dir(0); // Set direction
TMC2130A = &TMC2130Z;
}
setMotorStepWrite = &MovementAxis::setMotorStepWriteTMC2130;
@ -118,113 +102,32 @@ void MovementAxis::initTMC2130()
resetMotorStepWrite = &MovementAxis::resetMotorStepWriteTMC2130;
resetMotorStepWrite2 = &MovementAxis::resetMotorStepWriteTMC2130_2;
TMC2130A->init();
if (channelLabel == 'X')
{
TMC2130B->init();
}
}
void MovementAxis::loadSettingsTMC2130(int motorCurrent, int stallSensitivity, int microSteps)
{
/**/
/*
Serial.println("loading settings");
Serial.print("channelLabel");
Serial.print(" = ");
Serial.print(channelLabel);
Serial.println(" ");
Serial.print("motorCurrent");
Serial.print(" = ");
Serial.print(motorCurrent);
Serial.println(" ");
Serial.print("microSteps");
Serial.print(" = ");
Serial.print(microSteps);
Serial.println(" ");
Serial.print("stallSensitivity");
Serial.print(" = ");
Serial.print(stallSensitivity);
Serial.println(" = ");
*/
/*
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
*/
/*
TMC2130A->push();
TMC2130A->toff(3);
TMC2130A->tbl(1);
TMC2130A->hysteresis_start(4);
TMC2130A->hysteresis_end(-2);
TMC2130A->rms_current(motorCurrent); // mA
TMC2130A->microsteps(microSteps);
TMC2130A->diag1_stall(1);
TMC2130A->diag1_active_high(1);
TMC2130A->coolstep_min_speed(0xFFFFF); // 20bit max
TMC2130A->THIGH(0);
TMC2130A->semin(5);
TMC2130A->semax(2);
TMC2130A->sedn(0b01);
TMC2130A->sg_stall_value(stallSensitivity);
/*
TMC2130A->push();
TMC2130A->toff(3);
TMC2130A->tbl(1);
TMC2130A->hysteresis_start(4);
TMC2130A->hysteresis_end(-2);
TMC2130A->rms_current(600); // mA
TMC2130A->microsteps(16);
TMC2130A->diag1_stall(1);
TMC2130A->diag1_active_high(1);
TMC2130A->coolstep_min_speed(0xFFFFF); // 20bit max
TMC2130A->THIGH(0);
TMC2130A->semin(5);
TMC2130A->semax(2);
TMC2130A->sedn(0b01);
TMC2130A->sg_stall_value(0);
*/
loadTMC2130ParametersMotor(TMC2130A, microSteps, motorCurrent, stallSensitivity);
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
*/
/*
TMC2130B->push();
TMC2130B->toff(3);
TMC2130B->tbl(1);
TMC2130B->hysteresis_start(4);
TMC2130B->hysteresis_end(-2);
TMC2130B->rms_current(motorCurrent); // mA
TMC2130B->microsteps(microSteps);
TMC2130B->diag1_stall(1);
TMC2130B->diag1_active_high(1);
TMC2130B->coolstep_min_speed(0xFFFFF); // 20bit max
TMC2130B->THIGH(0);
TMC2130B->semin(5);
TMC2130B->semax(2);
TMC2130B->sedn(0b01);
TMC2130B->sg_stall_value(stallSensitivity);
*/
loadTMC2130ParametersMotor(TMC2130B, microSteps, motorCurrent, stallSensitivity);
}
}
bool MovementAxis::stallDetected() {
return TMC2130A->stallguard();
/**/
bool stallGuard = TMC2130A->getStatus() & FB_TMC_SPISTATUS_STALLGUARD_MASK ? true : false;
bool standStill = TMC2130A->getStatus() & FB_TMC_SPISTATUS_STANDSTILL_MASK ? true : false;
//return (TMC2130A->isStandstill() || TMC2130A->isStallguard());
//return stallGuard || standStill;
return false;
}
uint16_t MovementAxis::getLoad() {

View File

@ -16,10 +16,11 @@
#include "Config.h"
#include <stdio.h>
#include <stdlib.h>
#include "Board.h"
#if defined(FARMDUINO_EXP_V20)
//#if defined(FARMDUINO_EXP_V20)
#include "TMC2130.h"
#endif
//#endif
class MovementAxis
@ -29,8 +30,8 @@ public:
MovementAxis();
#if defined(FARMDUINO_EXP_V20)
TMC2130Stepper *TMC2130A;
TMC2130Stepper *TMC2130B;
TMC2130_Basics *TMC2130A;
TMC2130_Basics *TMC2130B;
#endif
void loadPinNumbers(int step, int dir, int enable, int min, int max, int step2, int dir2, int enable2);

View File

@ -5,70 +5,108 @@
* Author: Tim Evers
*/
#include "TMC2130.h"
/*
static TMC2130Stepper *TMC2130X;
static TMC2130Stepper *TMC2130Y;
static TMC2130Stepper *TMC2130Z;
static TMC2130Stepper *TMC2130E;
*/
#if defined(FARMDUINO_EXP_V20)
/*
static TMC2130Stepper TMC2130_X = TMC2130Stepper(X_ENABLE_PIN, X_DIR_PIN, X_STEP_PIN, X_CHIP_SELECT);
static TMC2130Stepper TMC2130_Y = TMC2130Stepper(Y_ENABLE_PIN, Y_DIR_PIN, Y_STEP_PIN, Y_CHIP_SELECT);
static TMC2130Stepper TMC2130_Z = TMC2130Stepper(Z_ENABLE_PIN, Z_DIR_PIN, Z_STEP_PIN, Z_CHIP_SELECT);
static TMC2130Stepper TMC2130_E = TMC2130Stepper(E_ENABLE_PIN, E_DIR_PIN, E_STEP_PIN, E_CHIP_SELECT);
*/
/*
static TMC2130Holder *instance;
TMC2130Holder *TMC2130Holder::getInstance()
//void loadTMC2130ParametersMotor(Trinamic_TMC2130 *myStepper, int microsteps, int current, int sensitivity)
void loadTMC2130ParametersMotor(TMC2130_Basics *tb, int microsteps, int current, int sensitivity)
{
if (!instance)
//Serial.print("==>");
//Serial.print(" ");
//Serial.print(microsteps);
//Serial.print(" ");
//Serial.print(current);
//Serial.print(" ");
//Serial.print(sensitivity);
//Serial.println(" ");
/**/
tb->init();
uint8_t data = 0;
switch (microsteps) {
case 1:
data = 8;
break;
case 2:
data = 7;
break;
case 4:
data = 6;
break;
case 8:
data = 5;
break;
case 16:
data = 4;
break;
case 32:
data = 3;
break;
case 64:
data = 2;
break;
case 128:
data = 1;
break;
}
tb->alter_REG(FB_TMC_REG_CHOPCONF, uint32_t(data) << FB_TMC_CHOPCONF_MRES, FB_TMC_CHOPCONF_MASKS[FB_TMC_CHOPCONF_MRES] << FB_TMC_CHOPCONF_MRES);
tb->set_GCONF(FB_TMC_GCONF_I_SCALE_ANALOG, 1);
// load drive current for motors
{
instance = new TMC2130Holder();
};
return instance;
};
uint16_t mA = current;
float multiplier = 0.5;
float RS = 0.11;
uint8_t CS = 32.0*1.41421*mA / 1000.0*(RS + 0.02) / 0.325 - 1;
// If Current Scale is too low, turn on high sensitivity R_sense and calculate again
if (CS < 16) {
CS = 32.0*1.41421*mA / 1000.0*(RS + 0.02) / 0.180 - 1;
}
{
uint32_t data;
// adding ihold
data = ((uint32_t(CS)&FB_TMC_IHOLD_MASK) << FB_TMC_IHOLD);
// adding irun
data |= ((uint32_t(CS)&FB_TMC_IRUN_MASK) << FB_TMC_IRUN);
// adding iholddelay
data |= ((uint32_t(16)&FB_TMC_IHOLDDELAY_MASK) << FB_TMC_IHOLDDELAY);
TMC2130Holder::TMC2130Holder()
{
}
// writing data
tb->write_REG(FB_TMC_REG_IHOLD_IRUN, data);
}
}
void TMC2130Holder::loadDrivers()
{
TMC2130Stepper TMC2130X = new TMC2130Stepper(X_ENABLE_PIN, X_DIR_PIN, X_STEP_PIN, X_CHIP_SELECT);
TMC2130Stepper TMC2130Y = new TMC2130Stepper(Y_ENABLE_PIN, Y_DIR_PIN, Y_STEP_PIN, Y_CHIP_SELECT);
TMC2130Stepper TMC2130Z = new TMC2130Stepper(Z_ENABLE_PIN, Z_DIR_PIN, Z_STEP_PIN, Z_CHIP_SELECT);
TMC2130Stepper TMC2130E = new TMC2130Stepper(E_ENABLE_PIN, E_DIR_PIN, E_STEP_PIN, E_CHIP_SELECT);
tb->set_CHOPCONF(FB_TMC_CHOPCONF_TOFF, 3);
tb->set_CHOPCONF(FB_TMC_CHOPCONF_TBL, 1);
tb->set_GCONF(FB_TMC_GCONF_DIAG1_STALL, 1);
tb->set_GCONF(FB_TMC_GCONF_DIAG1_ONSTATE, 1);
{
uint32_t data;
tmcTMC2130X = &TMC2130X;
tmcTMC2130Y = &TMC2130Y;
tmcTMC2130Z = &TMC2130Z;
tmcTMC2130E = &TMC2130E;
data = 0xFFFFF & FB_TMC_TCOOLTHRS_MASK;
tb->write_REG(FB_TMC_REG_TCOOLTHRS, data);
}
{
uint32_t data;
data = 0 & FB_TMC_THIGH_MASK;
tb->write_REG(FB_TMC_REG_THIGH, data);
}
{
tb->set_CHOPCONF(FB_TMC_COOLCONF_SEMIN, 5);
}
tb->set_CHOPCONF(FB_TMC_COOLCONF_SEMAX, 2);
tb->set_CHOPCONF(FB_TMC_COOLCONF_SEMAX, 0b01);
tb->set_CHOPCONF(FB_TMC_COOLCONF_SGT, sensitivity);
}
TMC2130Stepper* TMC2130Holder::TMC2130X()
{
return tmcTMC2130X;
}
TMC2130Stepper* TMC2130Holder::TMC2130Y()
{
return tmcTMC2130Y;
}
TMC2130Stepper* TMC2130Holder::TMC2130Z()
{
return tmcTMC2130Z;
}
c
TMC2130Stepper* TMC2130Holder::TMC2130E()
{
return tmcTMC213EZ;
}
*/
#endif

View File

@ -9,70 +9,20 @@
#ifndef TMC2130_H_
#define TMC2130_H_
//#include <TMC2130Stepper.h>
//#include <TMC2130Stepper_REGDEFS.h>
#include "TMC2130/TMC2130Stepper.h"
#include "TMC2130/TMC2130Stepper_REGDEFS.h"
#include <SPI.h>
#include "pins.h"
static TMC2130Stepper *TMC2130X;
static TMC2130Stepper *TMC2130Y;
static TMC2130Stepper *TMC2130Z;
static TMC2130Stepper *TMC2130E;
//static TMC2130Stepper TMC2130_X = TMC2130Stepper(X_ENABLE_PIN, X_DIR_PIN, X_STEP_PIN, X_CHIP_SELECT);
//static TMC2130Stepper TMC2130_Y = TMC2130Stepper(Y_ENABLE_PIN, Y_DIR_PIN, Y_STEP_PIN, Y_CHIP_SELECT);
//static TMC2130Stepper TMC2130_Z = TMC2130Stepper(Z_ENABLE_PIN, Z_DIR_PIN, Z_STEP_PIN, Z_CHIP_SELECT);
//static TMC2130Stepper TMC2130_E = 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 /* TMC2130_H_ */
/*
#include "Board.h"
#if defined(FARMDUINO_EXP_V20)
#include <TMC2130Stepper.h>
//#include "TMC2130Stepper.h"
#include "TMC2130_Basics.h"
static TMC2130_Basics TMC2130X(X_CHIP_SELECT);
static TMC2130_Basics TMC2130Y(Y_CHIP_SELECT);
static TMC2130_Basics TMC2130Z(Z_CHIP_SELECT);
static TMC2130_Basics TMC2130E(E_CHIP_SELECT);
void loadTMC2130ParametersMotor(TMC2130_Basics *tb, int microsteps, int current, int sensitivity);
#endif
#ifndef TMC2130Holder_H_
#define TMC2130Holder_H_
class TMC2130Holder
{
public:
TMC2130Holder();
TMC2130Holder(TMC2130Holder const &);
void operator=(TMC2130Holder const &);
static TMC2130Holder *getInstance();
void loadDrivers();
TMC2130Stepper* TMC2130X();
TMC2130Stepper* TMC2130Y();
TMC2130Stepper* TMC2130Z();
TMC2130Stepper* TMC2130E();
private:
static TMC2130Stepper *tmcTMC2130X;
static TMC2130Stepper *tmcTMC2130Y;
static TMC2130Stepper *tmcTMC2130Z;
static TMC2130Stepper *tmcTMC2130E;
};
#endif
*/
/* TMC2130Holder_H_ */
#endif /* TMC2130_H_ */

View File

@ -1,83 +0,0 @@
#include "SW_SPI.h"
SW_SPIClass TMC_SW_SPI;
#if defined(ARDUINO_ARCH_AVR)
#define getPort(P) digitalPinToPort(P)
#define writeMOSI_H *mosi_register |= mosi_bm
#define writeMOSI_L *mosi_register &= ~mosi_bm
#define writeSCK_H *sck_register |= sck_bm
#define writeSCK_L *sck_register &= ~sck_bm
#define readMISO *miso_register & miso_bm
#elif defined(ARDUINO_ARCH_SAM) // DUE:1.2MHz
// by stimmer https://forum.arduino.cc/index.php?topic=129868.msg980466#msg980466
#define writeMOSI_H g_APinDescription[mosi_pin].pPort -> PIO_SODR = g_APinDescription[mosi_pin].ulPin
#define writeMOSI_L g_APinDescription[mosi_pin].pPort -> PIO_CODR = g_APinDescription[mosi_pin].ulPin
#define writeSCK_H g_APinDescription[sck_pin].pPort -> PIO_SODR = g_APinDescription[sck_pin].ulPin
#define writeSCK_L g_APinDescription[sck_pin].pPort -> PIO_CODR = g_APinDescription[sck_pin].ulPin
#define readMISO !!(g_APinDescription[miso_pin].pPort -> PIO_PDSR & g_APinDescription[miso_pin].ulPin)
#else // DUE:116kHz
#define writeMOSI_H digitalWrite(mosi_pin, HIGH)
#define writeMOSI_L digitalWrite(mosi_pin, LOW)
#define writeSCK_H digitalWrite(sck_pin, HIGH)
#define writeSCK_L digitalWrite(sck_pin, LOW)
#define readMISO digitalRead(miso_pin)
#endif
void SW_SPIClass::setPins(uint16_t sw_mosi_pin, uint16_t sw_miso_pin, uint16_t sw_sck_pin) {
mosi_pin = sw_mosi_pin;
miso_pin = sw_miso_pin;
sck_pin = sw_sck_pin;
}
void SW_SPIClass::init() {
pinMode(mosi_pin, OUTPUT);
pinMode(sck_pin, OUTPUT);
pinMode(miso_pin, INPUT_PULLUP);
#ifndef TARGET_LPC1768
mosi_bm = digitalPinToBitMask(mosi_pin);
miso_bm = digitalPinToBitMask(miso_pin);
sck_bm = digitalPinToBitMask(sck_pin);
#ifdef ARDUINO_ARCH_AVR
mosi_register = portOutputRegister(getPort(mosi_pin));
miso_register = portInputRegister(getPort(miso_pin));
sck_register = portOutputRegister(getPort(sck_pin));
#endif
#endif
}
//Combined shiftOut and shiftIn from Arduino wiring_shift.c
byte SW_SPIClass::transfer(uint8_t ulVal, uint8_t ulBitOrder) {
uint8_t value = 0;
for (uint8_t i=0 ; i<8 ; ++i) {
// Write bit
if ( ulBitOrder == LSBFIRST ) {
!!(ulVal & (1 << i)) ? writeMOSI_H : writeMOSI_L;
} else {
!!(ulVal & (1 << (7 - i))) ? writeMOSI_H : writeMOSI_L;
}
// Start clock pulse
writeSCK_H;
// Read bit
if ( ulBitOrder == LSBFIRST ) {
value |= ( readMISO ? 1 : 0) << i ;
} else {
value |= ( readMISO ? 1 : 0) << (7 - i) ;
}
// Stop clock pulse
writeSCK_L;
}
return value;
}
uint16_t SW_SPIClass::transfer16(uint16_t data) {
uint16_t returnVal = 0x0000;
returnVal |= transfer((data>>8)&0xFF) << 8;
returnVal |= transfer(data&0xFF) & 0xFF;
return returnVal;
}

View File

@ -1,25 +0,0 @@
#pragma once
#include <Arduino.h>
class SW_SPIClass {
public:
void setPins(uint16_t sw_mosi_pin, uint16_t sw_miso_pin, uint16_t sw_sck_pin);
void init();
void begin() {};
byte transfer(uint8_t ulVal, uint8_t ulBitOrder=MSBFIRST);
uint16_t transfer16(uint16_t data);
void endTransaction() {};
private:
uint16_t mosi_pin,
miso_pin,
sck_pin;
uint8_t mosi_bm,
miso_bm,
sck_bm;
volatile uint8_t *mosi_register,
*miso_register,
*sck_register;
};
extern SW_SPIClass TMC_SW_SPI;

View File

@ -1,389 +0,0 @@
#include "TMC2130Stepper.h"
#include "TMC2130Stepper_MACROS.h"
#include <SPI.h>
TMC2130Stepper::TMC2130Stepper(uint16_t pinCS) : _pinCS(pinCS) {}
TMC2130Stepper::TMC2130Stepper(uint16_t pinEN, uint16_t pinDIR, uint16_t pinStep, uint16_t pinCS) :
_pinEN(pinEN),
_pinSTEP(pinStep),
_pinCS(pinCS),
_pinDIR(pinDIR)
{}
void TMC2130Stepper::begin() {
#ifdef TMC2130DEBUG
Serial.println("TMC2130 Stepper driver library");
Serial.print("Enable pin: ");
Serial.println(_pinEN);
Serial.print("Direction pin: ");
Serial.println(_pinDIR);
Serial.print("Step pin: ");
Serial.println(_pinSTEP);
Serial.print("Chip select pin: ");
Serial.println(_pinCS);
#endif
delay(200);
//set pins
if (_pinEN != 0xFFFF) {
pinMode(_pinEN, OUTPUT);
digitalWrite(_pinEN, HIGH); //deactivate driver (LOW active)
}
if (_pinDIR != 0xFFFF) {
pinMode(_pinDIR, OUTPUT);
}
if (_pinSTEP != 0xFFFF) {
pinMode(_pinSTEP, OUTPUT);
digitalWrite(_pinSTEP, LOW);
}
pinMode(_pinCS, OUTPUT);
digitalWrite(_pinCS, HIGH);
// Reset registers
push();
toff(8); //off_time(8);
tbl(1); //blank_time(24);
}
void TMC2130Stepper::send2130(uint8_t addressByte, uint32_t *config) {
SPI.begin();
SPI.beginTransaction(SPISettings(16000000/8, MSBFIRST, SPI_MODE3));
digitalWrite(_pinCS, LOW);
status_response = SPI.transfer(addressByte & 0xFF); // s =
if (addressByte >> 7) { // Check if WRITE command
//*config &= ~mask; // Clear bits being set
//*config |= (value & mask); // Set new values
SPI.transfer((*config >> 24) & 0xFF);
SPI.transfer((*config >> 16) & 0xFF);
SPI.transfer((*config >> 8) & 0xFF);
SPI.transfer(*config & 0xFF);
} else { // READ command
SPI.transfer16(0x0000); // Clear SPI
SPI.transfer16(0x0000);
digitalWrite(_pinCS, HIGH);
digitalWrite(_pinCS, LOW);
SPI.transfer(addressByte & 0xFF); // Send the address byte again
*config = SPI.transfer(0x00);
*config <<= 8;
*config|= SPI.transfer(0x00);
*config <<= 8;
*config|= SPI.transfer(0x00);
*config <<= 8;
*config|= SPI.transfer(0x00);
}
digitalWrite(_pinCS, HIGH);
SPI.endTransaction();
}
bool TMC2130Stepper::checkOT() {
uint32_t response = DRV_STATUS();
if (response & OTPW_bm) {
flag_otpw = 1;
return true; // bit 26 for overtemperature warning flag
}
return false;
}
bool TMC2130Stepper::getOTPW() { return flag_otpw; }
void TMC2130Stepper::clear_otpw() { flag_otpw = 0; }
bool TMC2130Stepper::isEnabled() { return !digitalRead(_pinEN) && toff(); }
void TMC2130Stepper::push() {
GCONF(GCONF_sr);
IHOLD_IRUN(IHOLD_IRUN_sr);
TPOWERDOWN(TPOWERDOWN_sr);
TPWMTHRS(TPWMTHRS_sr);
TCOOLTHRS(TCOOLTHRS_sr);
THIGH(THIGH_sr);
XDIRECT(XDIRECT_sr);
VDCMIN(VDCMIN_sr);
CHOPCONF(CHOPCONF_sr);
//MSLUT0(MSLUT0_sr);
//MSLUT1(MSLUT1_sr);
//MSLUT2(MSLUT2_sr);
//MSLUT3(MSLUT3_sr);
//MSLUT4(MSLUT4_sr);
//MSLUT5(MSLUT5_sr);
//MSLUT6(MSLUT6_sr);
//MSLUT7(MSLUT7_sr);
//MSLUT0(MSLUT0_sr);
//MSLUT0(MSLUT0_sr);
//MSLUTSTART(MSLUTSTART_sr);
COOLCONF(COOLCONF_sr);
PWMCONF(PWMCONF_sr);
ENCM_CTRL(ENCM_CTRL_sr);
}
uint8_t TMC2130Stepper::test_connection() {
uint32_t drv_status = DRV_STATUS();
switch (drv_status) {
case 0xFFFFFFFF: return 1;
case 0: return 2;
default: return 0;
}
}
///////////////////////////////////////////////////////////////////////////////////////
// R+C: GSTAT
void TMC2130Stepper::GSTAT(uint8_t input){
GSTAT_sr = input;
TMC_WRITE_REG(GSTAT);
}
uint8_t TMC2130Stepper::GSTAT() { TMC_READ_REG_R(GSTAT); }
bool TMC2130Stepper::reset() { TMC_GET_BYTE(GSTAT, RESET); }
bool TMC2130Stepper::drv_err() { TMC_GET_BYTE(GSTAT, DRV_ERR); }
bool TMC2130Stepper::uv_cp() { TMC_GET_BYTE(GSTAT, UV_CP); }
///////////////////////////////////////////////////////////////////////////////////////
// R: IOIN
uint32_t TMC2130Stepper::IOIN() { TMC_READ_REG_R(IOIN); }
bool TMC2130Stepper::step() { TMC_GET_BYTE_R(IOIN, STEP); }
bool TMC2130Stepper::dir() { TMC_GET_BYTE_R(IOIN, DIR); }
bool TMC2130Stepper::dcen_cfg4() { TMC_GET_BYTE_R(IOIN, DCEN_CFG4); }
bool TMC2130Stepper::dcin_cfg5() { TMC_GET_BYTE_R(IOIN, DCIN_CFG5); }
bool TMC2130Stepper::drv_enn_cfg6() { TMC_GET_BYTE_R(IOIN, DRV_ENN_CFG6); }
bool TMC2130Stepper::dco() { TMC_GET_BYTE_R(IOIN, DCO); }
uint8_t TMC2130Stepper::version() { TMC_GET_BYTE_R(IOIN, VERSION); }
///////////////////////////////////////////////////////////////////////////////////////
// W: TPOWERDOWN
uint8_t TMC2130Stepper::TPOWERDOWN() { return TPOWERDOWN_sr; }
void TMC2130Stepper::TPOWERDOWN(uint8_t input) {
TPOWERDOWN_sr = input;
TMC_WRITE_REG(TPOWERDOWN);
}
///////////////////////////////////////////////////////////////////////////////////////
// R: TSTEP
uint32_t TMC2130Stepper::TSTEP() { TMC_READ_REG_R(TSTEP); }
///////////////////////////////////////////////////////////////////////////////////////
// W: TPWMTHRS
uint32_t TMC2130Stepper::TPWMTHRS() { return TPWMTHRS_sr; }
void TMC2130Stepper::TPWMTHRS(uint32_t input) {
TPWMTHRS_sr = input;
TMC_WRITE_REG(TPWMTHRS);
}
///////////////////////////////////////////////////////////////////////////////////////
// W: TCOOLTHRS
uint32_t TMC2130Stepper::TCOOLTHRS() { return TCOOLTHRS_sr; }
void TMC2130Stepper::TCOOLTHRS(uint32_t input) {
TCOOLTHRS_sr = input;
TMC_WRITE_REG(TCOOLTHRS);
}
///////////////////////////////////////////////////////////////////////////////////////
// W: THIGH
uint32_t TMC2130Stepper::THIGH() { return THIGH_sr; }
void TMC2130Stepper::THIGH(uint32_t input) {
THIGH_sr = input;
TMC_WRITE_REG(THIGH);
}
///////////////////////////////////////////////////////////////////////////////////////
// RW: XDIRECT
uint32_t TMC2130Stepper::XDIRECT() { TMC_READ_REG(XDIRECT); }
void TMC2130Stepper::XDIRECT(uint32_t input) {
XDIRECT_sr = input;
TMC_WRITE_REG(XDIRECT);
}
void TMC2130Stepper::coil_A(int16_t B) { TMC_MOD_REG(XDIRECT, COIL_A); }
void TMC2130Stepper::coil_B(int16_t B) { TMC_MOD_REG(XDIRECT, COIL_B); }
int16_t TMC2130Stepper::coil_A() { TMC_GET_BYTE_R(XDIRECT, COIL_A); }
int16_t TMC2130Stepper::coil_B() { TMC_GET_BYTE_R(XDIRECT, COIL_A); }
///////////////////////////////////////////////////////////////////////////////////////
// W: VDCMIN
uint32_t TMC2130Stepper::VDCMIN() { return VDCMIN_sr; }
void TMC2130Stepper::VDCMIN(uint32_t input) {
VDCMIN_sr = input;
TMC_WRITE_REG(VDCMIN);
}
///////////////////////////////////////////////////////////////////////////////////////
// W: MSLUT
uint32_t TMC2130Stepper::MSLUT0() { return MSLUT0_sr; }
void TMC2130Stepper::MSLUT0(uint32_t input) {
MSLUT0_sr = input;
TMC_WRITE_REG(MSLUT0);
}
uint32_t TMC2130Stepper::MSLUT1() { return MSLUT1_sr; }
void TMC2130Stepper::MSLUT1(uint32_t input) {
MSLUT1_sr = input;
TMC_WRITE_REG(MSLUT1);
}
uint32_t TMC2130Stepper::MSLUT2() { return MSLUT2_sr; }
void TMC2130Stepper::MSLUT2(uint32_t input) {
MSLUT2_sr = input;
TMC_WRITE_REG(MSLUT2);
}
uint32_t TMC2130Stepper::MSLUT3() { return MSLUT3_sr; }
void TMC2130Stepper::MSLUT3(uint32_t input) {
MSLUT3_sr = input;
TMC_WRITE_REG(MSLUT3);
}
uint32_t TMC2130Stepper::MSLUT4() { return MSLUT4_sr; }
void TMC2130Stepper::MSLUT4(uint32_t input) {
MSLUT4_sr = input;
TMC_WRITE_REG(MSLUT4);
}
uint32_t TMC2130Stepper::MSLUT5() { return MSLUT5_sr; }
void TMC2130Stepper::MSLUT5(uint32_t input) {
MSLUT0_sr = input;
TMC_WRITE_REG(MSLUT5);
}
uint32_t TMC2130Stepper::MSLUT6() { return MSLUT6_sr; }
void TMC2130Stepper::MSLUT6(uint32_t input) {
MSLUT0_sr = input;
TMC_WRITE_REG(MSLUT6);
}
uint32_t TMC2130Stepper::MSLUT7() { return MSLUT7_sr; }
void TMC2130Stepper::MSLUT7(uint32_t input) {
MSLUT0_sr = input;
TMC_WRITE_REG(MSLUT7);
}
///////////////////////////////////////////////////////////////////////////////////////
// W: MSLUTSEL
uint32_t TMC2130Stepper::MSLUTSEL() { return MSLUTSEL_sr; }
void TMC2130Stepper::MSLUTSEL(uint32_t input) {
MSLUTSEL_sr = input;
TMC_WRITE_REG(MSLUTSEL);
}
///////////////////////////////////////////////////////////////////////////////////////
// W: MSLUTSTART
uint32_t TMC2130Stepper::MSLUTSTART() { return MSLUTSTART_sr; }
void TMC2130Stepper::MSLUTSTART(uint32_t input) {
MSLUTSTART_sr = input;
TMC_WRITE_REG(MSLUTSTART);
}
///////////////////////////////////////////////////////////////////////////////////////
// R: MSCNT
uint16_t TMC2130Stepper::MSCNT() { TMC_READ_REG_R(MSCNT); }
///////////////////////////////////////////////////////////////////////////////////////
// R: MSCURACT
uint32_t TMC2130Stepper::MSCURACT() { TMC_READ_REG_R(MSCURACT); }
int16_t TMC2130Stepper::cur_a() {
int16_t value = (MSCURACT()&CUR_A_bm) >> CUR_A_bp;
if (value > 255) value -= 512;
return value;
}
int16_t TMC2130Stepper::cur_b() {
int16_t value = (MSCURACT()&CUR_B_bm) >> CUR_B_bp;
if (value > 255) value -= 512;
return value;
}
///////////////////////////////////////////////////////////////////////////////////////
// R: PWM_SCALE
uint8_t TMC2130Stepper::PWM_SCALE() { TMC_READ_REG_R(PWM_SCALE); }
///////////////////////////////////////////////////////////////////////////////////////
// W: ENCM_CTRL
uint8_t TMC2130Stepper::ENCM_CTRL() { return ENCM_CTRL_sr; }
void TMC2130Stepper::ENCM_CTRL(uint8_t input) {
ENCM_CTRL_sr = input;
TMC_WRITE_REG(ENCM_CTRL);
}
void TMC2130Stepper::inv(bool B) { TMC_MOD_REG(ENCM_CTRL, INV); }
void TMC2130Stepper::maxspeed(bool B) { TMC_MOD_REG(ENCM_CTRL, MAXSPEED); }
bool TMC2130Stepper::inv() { TMC_GET_BYTE(ENCM_CTRL, INV); }
bool TMC2130Stepper::maxspeed() { TMC_GET_BYTE(ENCM_CTRL, MAXSPEED);}
///////////////////////////////////////////////////////////////////////////////////////
// R: LOST_STEPS
uint32_t TMC2130Stepper::LOST_STEPS() { TMC_READ_REG_R(LOST_STEPS); }
/**
* Helper functions
*/
/*
Requested current = mA = I_rms/1000
Equation for current:
I_rms = (CS+1)/32 * V_fs/(R_sense+0.02ohm) * 1/sqrt(2)
Solve for CS ->
CS = 32*sqrt(2)*I_rms*(R_sense+0.02)/V_fs - 1
Example:
vsense = 0b0 -> V_fs = 0.325V
mA = 1640mA = I_rms/1000 = 1.64A
R_sense = 0.10 Ohm
->
CS = 32*sqrt(2)*1.64*(0.10+0.02)/0.325 - 1 = 26.4
CS = 26
*/
void TMC2130Stepper::rms_current(uint16_t mA, float multiplier, float RS) {
Rsense = RS;
uint8_t CS = 32.0*1.41421*mA/1000.0*(Rsense+0.02)/0.325 - 1;
// If Current Scale is too low, turn on high sensitivity R_sense and calculate again
if (CS < 16) {
vsense(true);
CS = 32.0*1.41421*mA/1000.0*(Rsense+0.02)/0.180 - 1;
} else if(vsense()) { // If CS >= 16, turn off high_sense_r if it's currently ON
vsense(false);
}
irun(CS);
ihold(CS*multiplier);
val_mA = mA;
}
uint16_t TMC2130Stepper::rms_current() {
return (float)(irun()+1)/32.0 * (vsense()?0.180:0.325)/(Rsense+0.02) / 1.41421 * 1000;
}
void TMC2130Stepper::setCurrent(uint16_t mA, float R, float multiplier) { rms_current(mA, multiplier, R); }
uint16_t TMC2130Stepper::getCurrent() { return val_mA; }
void TMC2130Stepper::SilentStepStick2130(uint16_t current) { rms_current(current); }
void TMC2130Stepper::microsteps(uint16_t ms) {
switch(ms) {
case 256: mres(0); break;
case 128: mres(1); break;
case 64: mres(2); break;
case 32: mres(3); break;
case 16: mres(4); break;
case 8: mres(5); break;
case 4: mres(6); break;
case 2: mres(7); break;
case 0: mres(8); break;
default: break;
}
}
uint16_t TMC2130Stepper::microsteps() {
switch(mres()) {
case 0: return 256;
case 1: return 128;
case 2: return 64;
case 3: return 32;
case 4: return 16;
case 5: return 8;
case 6: return 4;
case 7: return 2;
case 8: return 0;
}
return 0;
}
void TMC2130Stepper::sg_current_decrease(uint8_t value) {
switch(value) {
case 32: sedn(0b00); break;
case 8: sedn(0b01); break;
case 2: sedn(0b10); break;
case 1: sedn(0b11); break;
}
}
uint8_t TMC2130Stepper::sg_current_decrease() {
switch(sedn()) {
case 0b00: return 32;
case 0b01: return 8;
case 0b10: return 2;
case 0b11: return 1;
}
return 0;
}

View File

@ -1,447 +0,0 @@
#pragma once
//#define TMC2130DEBUG
#include <Arduino.h>
#include <stdint.h>
#include <SPI.h>
#define TMC2130STEPPER_VERSION 0x020500 // v2.5.0
class TMC2130Stepper {
public:
TMC2130Stepper(uint16_t pinCS);
TMC2130Stepper(uint16_t pinEN, uint16_t pinDIR, uint16_t pinStep, uint16_t pinCS);
TMC2130Stepper(uint16_t pinEN, uint16_t pinDIR, uint16_t pinStep, uint16_t pinCS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK);
void changeChipSelect(uint16_t pinCS);
void begin();
void checkStatus();
void rms_current(uint16_t mA, float multiplier=0.5, float RS=0.11);
uint16_t rms_current();
void SilentStepStick2130(uint16_t mA);
void setCurrent(uint16_t mA, float Rsense, float multiplier);
uint16_t getCurrent();
bool checkOT();
bool getOTPW();
void clear_otpw();
bool isEnabled();
void push();
uint8_t test_connection();
// GCONF
uint32_t GCONF();
void GCONF( uint32_t value);
void I_scale_analog( bool B);
void internal_Rsense( bool B);
void en_pwm_mode( bool B);
void enc_commutation( bool B);
void shaft( bool B);
void diag0_error( bool B);
void diag0_otpw( bool B);
void diag0_stall( bool B);
void diag1_stall( bool B);
void diag1_index( bool B);
void diag1_onstate( bool B);
void diag1_steps_skipped( bool B);
void diag0_int_pushpull( bool B);
void diag1_pushpull( bool B);
void small_hysteresis( bool B);
void stop_enable( bool B);
void direct_mode( bool B);
bool I_scale_analog();
bool internal_Rsense();
bool en_pwm_mode();
bool enc_commutation();
bool shaft();
bool diag0_error();
bool diag0_otpw();
bool diag0_stall();
bool diag1_stall();
bool diag1_index();
bool diag1_onstate();
bool diag1_steps_skipped();
bool diag0_int_pushpull();
bool diag1_pushpull();
bool small_hysteresis();
bool stop_enable();
bool direct_mode();
// IHOLD_IRUN
void IHOLD_IRUN( uint32_t input);
uint32_t IHOLD_IRUN();
void ihold( uint8_t B);
void irun( uint8_t B);
void iholddelay( uint8_t B);
uint8_t ihold();
uint8_t irun();
uint8_t iholddelay();
// GSTAT
void GSTAT( uint8_t input);
uint8_t GSTAT();
bool reset();
bool drv_err();
bool uv_cp();
// IOIN
uint32_t IOIN();
bool step();
bool dir();
bool dcen_cfg4();
bool dcin_cfg5();
bool drv_enn_cfg6();
bool dco();
uint8_t version();
// TPOWERDOWN
uint8_t TPOWERDOWN();
void TPOWERDOWN( uint8_t input);
// TSTEP
uint32_t TSTEP();
// TPWMTHRS
uint32_t TPWMTHRS();
void TPWMTHRS( uint32_t input);
// TCOOLTHRS
uint32_t TCOOLTHRS();
void TCOOLTHRS( uint32_t input);
// THIGH
uint32_t THIGH();
void THIGH( uint32_t input);
// XDRIRECT
uint32_t XDIRECT();
void XDIRECT( uint32_t input);
void coil_A( int16_t B);
void coil_B( int16_t B);
int16_t coil_A();
int16_t coil_B();
// VDCMIN
uint32_t VDCMIN();
void VDCMIN( uint32_t input);
// MSLUT0..MSLUT7
uint32_t MSLUT0();
void MSLUT0( uint32_t input);
uint32_t MSLUT1();
void MSLUT1( uint32_t input);
uint32_t MSLUT2();
void MSLUT2( uint32_t input);
uint32_t MSLUT3();
void MSLUT3( uint32_t input);
uint32_t MSLUT4();
void MSLUT4( uint32_t input);
uint32_t MSLUT5();
void MSLUT5( uint32_t input);
uint32_t MSLUT6();
void MSLUT6( uint32_t input);
uint32_t MSLUT7();
void MSLUT7( uint32_t input);
// MSLUTSEL
uint32_t MSLUTSEL();
void MSLUTSEL( uint32_t input);
// MSLUTSTART
uint32_t MSLUTSTART();
void MSLUTSTART( uint32_t input);
// MSCNT
uint16_t MSCNT();
// MSCURACT
uint32_t MSCURACT();
int16_t cur_a();
int16_t cur_b();
// CHOPCONF
uint32_t CHOPCONF();
void CHOPCONF( uint32_t value);
void toff( uint8_t B);
void hstrt( uint8_t B);
void hend( uint8_t B);
void fd( uint8_t B);
void disfdcc( bool B);
void rndtf( bool B);
void chm( bool B);
void tbl( uint8_t B);
void vsense( bool B);
void vhighfs( bool B);
void vhighchm( bool B);
void sync( uint8_t B);
void mres( uint8_t B);
void intpol( bool B);
void dedge( bool B);
void diss2g( bool B);
uint8_t toff();
uint8_t hstrt();
uint8_t hend();
uint8_t fd();
bool disfdcc();
bool rndtf();
bool chm();
uint8_t tbl();
bool vsense();
bool vhighfs();
bool vhighchm();
uint8_t sync();
uint8_t mres();
bool intpol();
bool dedge();
bool diss2g();
// COOLCONF
void COOLCONF(uint32_t value);
uint32_t COOLCONF();
void semin( uint8_t B);
void seup( uint8_t B);
void semax( uint8_t B);
void sedn( uint8_t B);
void seimin( bool B);
void sgt( int8_t B);
void sfilt( bool B);
uint8_t semin();
uint8_t seup();
uint8_t semax();
uint8_t sedn();
bool seimin();
int8_t sgt();
bool sfilt();
// PWMCONF
void PWMCONF( uint32_t value);
uint32_t PWMCONF();
void pwm_ampl( uint8_t B);
void pwm_grad( uint8_t B);
void pwm_freq( uint8_t B);
void pwm_autoscale( bool B);
void pwm_symmetric( bool B);
void freewheel( uint8_t B);
uint8_t pwm_ampl();
uint8_t pwm_grad();
uint8_t pwm_freq();
bool pwm_autoscale();
bool pwm_symmetric();
uint8_t freewheel();
// DRVSTATUS
uint32_t DRV_STATUS();
uint16_t sg_result();
bool fsactive();
uint8_t cs_actual();
bool stallguard();
bool ot();
bool otpw();
bool s2ga();
bool s2gb();
bool ola();
bool olb();
bool stst();
// PWM_SCALE
uint8_t PWM_SCALE();
// ENCM_CTRL
uint8_t ENCM_CTRL();
void ENCM_CTRL( uint8_t input);
void inv( bool B);
void maxspeed( bool B);
bool inv();
bool maxspeed();
// LOST_STEPS
uint32_t LOST_STEPS();
// Helper functions
void microsteps(uint16_t ms);
uint16_t microsteps();
void blank_time(uint8_t value);
uint8_t blank_time();
void hysteresis_end(int8_t value);
int8_t hysteresis_end();
void hysteresis_start(uint8_t value);
uint8_t hysteresis_start();
void sg_current_decrease(uint8_t value);
uint8_t sg_current_decrease();
// Aliases
// RW: GCONF
inline bool external_ref() __attribute__((always_inline)) { return I_scale_analog(); }
inline bool internal_sense_R() __attribute__((always_inline)) { return internal_Rsense(); }
inline bool stealthChop() __attribute__((always_inline)) { return en_pwm_mode(); }
inline bool commutation() __attribute__((always_inline)) { return enc_commutation(); }
inline bool shaft_dir() __attribute__((always_inline)) { return shaft(); }
inline bool diag0_errors() __attribute__((always_inline)) { return diag0_error(); }
inline bool diag0_temp_prewarn() __attribute__((always_inline)) { return diag0_otpw(); }
inline bool diag1_chopper_on() __attribute__((always_inline)) { return diag1_onstate(); }
inline bool diag0_active_high() __attribute__((always_inline)) { return diag0_int_pushpull(); }
inline bool diag1_active_high() __attribute__((always_inline)) { return diag1_pushpull(); }
inline void external_ref( bool value) __attribute__((always_inline)) { I_scale_analog(value); }
inline void internal_sense_R( bool value) __attribute__((always_inline)) { internal_Rsense(value); }
inline void stealthChop( bool value) __attribute__((always_inline)) { en_pwm_mode(value); }
inline void commutation( bool value) __attribute__((always_inline)) { enc_commutation(value); }
inline void shaft_dir( bool value) __attribute__((always_inline)) { shaft(value); }
inline void diag0_errors( bool value) __attribute__((always_inline)) { diag0_error(value); }
inline void diag0_temp_prewarn( bool value) __attribute__((always_inline)) { diag0_otpw(value); }
inline void diag1_chopper_on( bool value) __attribute__((always_inline)) { diag1_onstate(value); }
inline void diag0_active_high( bool value) __attribute__((always_inline)) { diag0_int_pushpull(value); }
inline void diag1_active_high( bool value) __attribute__((always_inline)) { diag1_pushpull(value); }
// RC
inline uint8_t status_flags() __attribute__((always_inline)) { return GSTAT(); }
// R
inline uint32_t input() __attribute__((always_inline)) { return IOIN(); }
// W: IHOLD_IRUN
inline uint8_t hold_current() __attribute__((always_inline)) { return ihold(); }
inline uint8_t run_current() __attribute__((always_inline)) { return irun(); }
inline uint8_t hold_delay() __attribute__((always_inline)) { return iholddelay(); }
inline void hold_current( uint8_t value) __attribute__((always_inline)) { ihold(value); }
inline void run_current( uint8_t value) __attribute__((always_inline)) { irun(value); }
inline void hold_delay( uint8_t value) __attribute__((always_inline)) { iholddelay(value); }
// W
inline uint8_t power_down_delay() __attribute__((always_inline)) { return TPOWERDOWN(); }
inline void power_down_delay( uint8_t value) __attribute__((always_inline)) { TPOWERDOWN(value); }
// R
inline uint32_t microstep_time() __attribute__((always_inline)) { return TSTEP(); }
// W
inline uint32_t stealth_max_speed() __attribute__((always_inline)) { return TPWMTHRS(); }
inline void stealth_max_speed(uint32_t value) __attribute__((always_inline)) { TPWMTHRS(value); }
// W
inline uint32_t coolstep_min_speed() __attribute__((always_inline)) { return TCOOLTHRS(); }
inline void coolstep_min_speed(uint32_t value) __attribute__((always_inline)) { TCOOLTHRS(value); }
// W
inline uint32_t mode_sw_speed() __attribute__((always_inline)) { return THIGH(); }
inline void mode_sw_speed( uint32_t value) __attribute__((always_inline)) { THIGH(value); }
// RW: XDIRECT
inline int16_t coil_A_current() __attribute__((always_inline)) { return coil_A(); }
inline void coil_A_current( int16_t value) __attribute__((always_inline)) { coil_B(value); }
inline int16_t coil_B_current() __attribute__((always_inline)) { return coil_A(); }
inline void coil_B_current( int16_t value) __attribute__((always_inline)) { coil_B(value); }
// W
inline uint32_t DCstep_min_speed() __attribute__((always_inline)) { return VDCMIN(); }
inline void DCstep_min_speed( uint32_t value) __attribute__((always_inline)) { VDCMIN(value); }
// W
inline uint32_t lut_mslutstart() __attribute__((always_inline)) { return MSLUTSTART(); }
inline void lut_mslutstart( uint32_t value) __attribute__((always_inline)) { MSLUTSTART(value); }
inline uint32_t lut_msutsel() __attribute__((always_inline)) { return MSLUTSEL(); }
inline void lut_msutsel( uint32_t value) __attribute__((always_inline)) { MSLUTSEL(value); }
inline uint32_t ms_lookup_0() __attribute__((always_inline)) { return MSLUT0(); }
inline void ms_lookup_0( uint32_t value) __attribute__((always_inline)) { MSLUT0(value); }
inline uint32_t ms_lookup_1() __attribute__((always_inline)) { return MSLUT1(); }
inline void ms_lookup_1( uint32_t value) __attribute__((always_inline)) { MSLUT1(value); }
inline uint32_t ms_lookup_2() __attribute__((always_inline)) { return MSLUT2(); }
inline void ms_lookup_2( uint32_t value) __attribute__((always_inline)) { MSLUT2(value); }
inline uint32_t ms_lookup_3() __attribute__((always_inline)) { return MSLUT3(); }
inline void ms_lookup_3( uint32_t value) __attribute__((always_inline)) { MSLUT3(value); }
inline uint32_t ms_lookup_4() __attribute__((always_inline)) { return MSLUT4(); }
inline void ms_lookup_4( uint32_t value) __attribute__((always_inline)) { MSLUT4(value); }
inline uint32_t ms_lookup_5() __attribute__((always_inline)) { return MSLUT5(); }
inline void ms_lookup_5( uint32_t value) __attribute__((always_inline)) { MSLUT5(value); }
inline uint32_t ms_lookup_6() __attribute__((always_inline)) { return MSLUT6(); }
inline void ms_lookup_6( uint32_t value) __attribute__((always_inline)) { MSLUT6(value); }
inline uint32_t ms_lookup_7() __attribute__((always_inline)) { return MSLUT7(); }
inline void ms_lookup_7( uint32_t value) __attribute__((always_inline)) { MSLUT7(value); }
// RW: CHOPCONF
inline uint8_t off_time() __attribute__((always_inline)) { return toff(); }
// inline uint8_t hysteresis_start() __attribute__((always_inline)) { return hstrt(); }
// inline int8_t hysteresis_low() __attribute__((always_inline)) { return hend(); }
inline int8_t hysteresis_low() __attribute__((always_inline)) { return hysteresis_end(); }
inline uint8_t fast_decay_time() __attribute__((always_inline)) { return fd(); }
inline bool disable_I_comparator() __attribute__((always_inline)) { return disfdcc(); }
inline bool random_off_time() __attribute__((always_inline)) { return rndtf(); }
inline bool chopper_mode() __attribute__((always_inline)) { return chm(); }
// inline uint8_t blank_time() __attribute__((always_inline)) { return tbl(); }
inline bool high_sense_R() __attribute__((always_inline)) { return vsense(); }
inline bool fullstep_threshold() __attribute__((always_inline)) { return vhighfs(); }
inline bool high_speed_mode() __attribute__((always_inline)) { return vhighchm(); }
inline uint8_t sync_phases() __attribute__((always_inline)) { return sync(); }
// inline uint16_t microsteps() __attribute__((always_inline)) { return mres(); }
inline bool interpolate() __attribute__((always_inline)) { return intpol(); }
inline bool double_edge_step() __attribute__((always_inline)) { return dedge(); }
inline bool disable_short_protection() __attribute__((always_inline)) { return diss2g(); }
inline void off_time( uint8_t value) __attribute__((always_inline)) { toff(value); }
// inline void hysteresis_start( uint8_t value) __attribute__((always_inline)) { hstrt(value); }
// inline void hysteresis_low( int8_t value) __attribute__((always_inline)) { hend(value); }
inline void hysteresis_low( int8_t value) __attribute__((always_inline)) { hysteresis_end(value); }
inline void fast_decay_time( uint8_t value) __attribute__((always_inline)) { fd(value); }
inline void disable_I_comparator( bool value) __attribute__((always_inline)) { disfdcc(value); }
inline void random_off_time( bool value) __attribute__((always_inline)) { rndtf(value); }
inline void chopper_mode( bool value) __attribute__((always_inline)) { chm(value); }
// inline void blank_time( uint8_t value) __attribute__((always_inline)) { tbl(value); }
inline void high_sense_R( bool value) __attribute__((always_inline)) { vsense(value); }
inline void fullstep_threshold( bool value) __attribute__((always_inline)) { vhighfs(value); }
inline void high_speed_mode( bool value) __attribute__((always_inline)) { vhighchm(value); }
inline void sync_phases( uint8_t value) __attribute__((always_inline)) { sync(value); }
// inline void microsteps( uint16_t value) __attribute__((always_inline)) { mres(value); }
inline void interpolate( bool value) __attribute__((always_inline)) { intpol(value); }
inline void double_edge_step( bool value) __attribute__((always_inline)) { dedge(value); }
inline void disable_short_protection(bool value)__attribute__((always_inline)) { diss2g(value); }
// W: COOLCONF
inline uint8_t sg_min() __attribute__((always_inline)) { return semin(); }
inline uint8_t sg_step_width() __attribute__((always_inline)) { return seup(); }
inline uint8_t sg_max() __attribute__((always_inline)) { return semax(); }
// inline uint8_t sg_current_decrease() __attribute__((always_inline)) { return sedn(); }
inline uint8_t smart_min_current() __attribute__((always_inline)) { return seimin(); }
inline int8_t sg_stall_value() __attribute__((always_inline)) { return sgt(); }
inline bool sg_filter() __attribute__((always_inline)) { return sfilt(); }
inline void sg_min( uint8_t value) __attribute__((always_inline)) { semin(value); }
inline void sg_step_width( uint8_t value) __attribute__((always_inline)) { seup(value); }
inline void sg_max( uint8_t value) __attribute__((always_inline)) { semax(value); }
// inline void sg_current_decrease(uint8_t value)__attribute__((always_inline)) { sedn(value); }
inline void smart_min_current( uint8_t value) __attribute__((always_inline)) { seimin(value); }
inline void sg_stall_value( int8_t value) __attribute__((always_inline)) { sgt(value); }
inline void sg_filter( bool value) __attribute__((always_inline)) { sfilt(value); }
// W: PWMCONF
inline uint8_t stealth_amplitude() __attribute__((always_inline)) { return pwm_ampl(); }
inline uint8_t stealth_gradient() __attribute__((always_inline)) { return pwm_grad(); }
inline uint8_t stealth_freq() __attribute__((always_inline)) { return pwm_freq(); }
inline bool stealth_autoscale() __attribute__((always_inline)) { return pwm_autoscale(); }
inline bool stealth_symmetric() __attribute__((always_inline)) { return pwm_symmetric(); }
inline uint8_t standstill_mode() __attribute__((always_inline)) { return freewheel(); }
inline void stealth_amplitude( uint8_t value) __attribute__((always_inline)) { pwm_ampl(value); }
inline void stealth_gradient( uint8_t value) __attribute__((always_inline)) { pwm_grad(value); }
inline void stealth_freq( uint8_t value) __attribute__((always_inline)) { pwm_freq(value); }
inline void stealth_autoscale( bool value) __attribute__((always_inline)) { pwm_autoscale(value); }
inline void stealth_symmetric( bool value) __attribute__((always_inline)) { pwm_symmetric(value); }
inline void standstill_mode( uint8_t value) __attribute__((always_inline)) { freewheel(value); }
// W: ENCM_CTRL
inline bool invert_encoder() __attribute__((always_inline)) { return inv(); }
inline void invert_encoder( bool value) __attribute__((always_inline)) { inv(value); }
// R: DRV_STATUS
inline uint32_t DRVSTATUS() __attribute__((always_inline)) { return DRV_STATUS(); }
// Backwards compatibility
inline void hysterisis_end(int8_t value) __attribute__((always_inline)) { hysteresis_end(value); }
inline int8_t hysterisis_end() __attribute__((always_inline)) { return hysteresis_end(); }
inline void hysterisis_start(uint8_t value) __attribute__((always_inline)) { hysteresis_start(value); }
inline uint8_t hysterisis_start() __attribute__((always_inline)) { return hysteresis_start(); }
float Rsense = 0.11;
uint8_t status_response;
bool flag_otpw = false;
private:
//const uint8_t WRITE = 0b10000000;
//const uint8_t READ = 0b00000000;
const uint16_t _pinEN = 0xFFFF;
const uint16_t _pinSTEP = 0xFFFF;
const uint16_t _pinCS = 0xFFFF;
//const int MOSI_PIN = 12;
//const int MISO_PIN = 11;
//const int SCK_PIN = 13;
const uint16_t _pinDIR = 0xFFFF;
// Shadow registers
uint32_t GCONF_sr = 0x00000000UL,
IHOLD_IRUN_sr = 0x00000000UL,
TSTEP_sr = 0x00000000UL,
TPWMTHRS_sr = 0x00000000UL,
TCOOLTHRS_sr = 0x00000000UL,
THIGH_sr = 0x00000000UL,
XDIRECT_sr = 0x00000000UL,
VDCMIN_sr = 0x00000000UL,
MSLUT0_sr = 0xAAAAB554UL,
MSLUT1_sr = 0x4A9554AAUL,
MSLUT2_sr = 0x24492929UL,
MSLUT3_sr = 0x10104222UL,
MSLUT4_sr = 0xFBFFFFFFUL,
MSLUT5_sr = 0xB5BB777DUL,
MSLUT6_sr = 0x49295556UL,
MSLUT7_sr = 0x00404222UL,
MSLUTSEL_sr = 0xFFFF8056UL,
CHOPCONF_sr = 0x00000000UL,
COOLCONF_sr = 0x00000000UL,
DCCTRL_sr = 0x00000000UL,
PWMCONF_sr = 0x00050480UL,
tmp_sr = 0x00000000UL,
TPOWERDOWN_sr = 0x00000000UL,
ENCM_CTRL_sr = 0x00000000UL,
GSTAT_sr = 0x00000000UL,
MSLUTSTART_sr = 0x00F70000UL;
void send2130(uint8_t addressByte, uint32_t *config);
uint16_t val_mA = 0;
const bool uses_sw_spi;
};

View File

@ -1,68 +0,0 @@
#include "TMC2130Stepper.h"
#include "TMC2130Stepper_MACROS.h"
// CHOPCONF
uint32_t TMC2130Stepper::CHOPCONF() { TMC_READ_REG(CHOPCONF); }
void TMC2130Stepper::CHOPCONF(uint32_t input) {
CHOPCONF_sr = input;
TMC_WRITE_REG(CHOPCONF);
}
void TMC2130Stepper::toff( uint8_t B ) { TMC_MOD_REG(CHOPCONF, TOFF); }
void TMC2130Stepper::hstrt( uint8_t B ) { TMC_MOD_REG(CHOPCONF, HSTRT); }
void TMC2130Stepper::hend( uint8_t B ) { TMC_MOD_REG(CHOPCONF, HEND); }
void TMC2130Stepper::fd( uint8_t B ) { TMC_MOD_REG(CHOPCONF, FD); }
void TMC2130Stepper::disfdcc( bool B ) { TMC_MOD_REG(CHOPCONF, DISFDCC); }
void TMC2130Stepper::rndtf( bool B ) { TMC_MOD_REG(CHOPCONF, RNDTF); }
void TMC2130Stepper::chm( bool B ) { TMC_MOD_REG(CHOPCONF, CHM); }
void TMC2130Stepper::tbl( uint8_t B ) { TMC_MOD_REG(CHOPCONF, TBL); }
void TMC2130Stepper::vsense( bool B ) { TMC_MOD_REG(CHOPCONF, VSENSE); }
void TMC2130Stepper::vhighfs( bool B ) { TMC_MOD_REG(CHOPCONF, VHIGHFS); }
void TMC2130Stepper::vhighchm( bool B ) { TMC_MOD_REG(CHOPCONF, VHIGHCHM); }
void TMC2130Stepper::sync( uint8_t B ) { TMC_MOD_REG(CHOPCONF, SYNC); }
void TMC2130Stepper::mres( uint8_t B ) { TMC_MOD_REG(CHOPCONF, MRES); }
void TMC2130Stepper::intpol( bool B ) { TMC_MOD_REG(CHOPCONF, INTPOL); }
void TMC2130Stepper::dedge( bool B ) { TMC_MOD_REG(CHOPCONF, DEDGE); }
void TMC2130Stepper::diss2g( bool B ) { TMC_MOD_REG(CHOPCONF, DISS2G); }
uint8_t TMC2130Stepper::toff() { TMC_GET_BYTE(CHOPCONF, TOFF); }
uint8_t TMC2130Stepper::hstrt() { TMC_GET_BYTE(CHOPCONF, HSTRT); }
uint8_t TMC2130Stepper::hend() { TMC_GET_BYTE(CHOPCONF, HEND); }
uint8_t TMC2130Stepper::fd() { TMC_GET_BYTE(CHOPCONF, FD); }
bool TMC2130Stepper::disfdcc() { TMC_GET_BYTE(CHOPCONF, DISFDCC); }
bool TMC2130Stepper::rndtf() { TMC_GET_BYTE(CHOPCONF, RNDTF); }
bool TMC2130Stepper::chm() { TMC_GET_BYTE(CHOPCONF, CHM); }
uint8_t TMC2130Stepper::tbl() { TMC_GET_BYTE(CHOPCONF, TBL); }
bool TMC2130Stepper::vsense() { TMC_GET_BIT( CHOPCONF, VSENSE); }
bool TMC2130Stepper::vhighfs() { TMC_GET_BYTE(CHOPCONF, VHIGHFS); }
bool TMC2130Stepper::vhighchm() { TMC_GET_BYTE(CHOPCONF, VHIGHCHM); }
uint8_t TMC2130Stepper::sync() { TMC_GET_BYTE(CHOPCONF, SYNC); }
uint8_t TMC2130Stepper::mres() { TMC_GET_BYTE(CHOPCONF, MRES); }
bool TMC2130Stepper::intpol() { TMC_GET_BYTE(CHOPCONF, INTPOL); }
bool TMC2130Stepper::dedge() { TMC_GET_BYTE(CHOPCONF, DEDGE); }
bool TMC2130Stepper::diss2g() { TMC_GET_BYTE(CHOPCONF, DISS2G); }
void TMC2130Stepper::hysteresis_end(int8_t value) { hend(value+3); }
int8_t TMC2130Stepper::hysteresis_end() { return hend()-3; };
void TMC2130Stepper::hysteresis_start(uint8_t value) { hstrt(value-1); }
uint8_t TMC2130Stepper::hysteresis_start() { return hstrt()+1; }
void TMC2130Stepper::blank_time(uint8_t value) {
switch (value) {
case 16: tbl(0b00); break;
case 24: tbl(0b01); break;
case 36: tbl(0b10); break;
case 54: tbl(0b11); break;
}
}
uint8_t TMC2130Stepper::blank_time() {
switch (tbl()) {
case 0b00: return 16;
case 0b01: return 24;
case 0b10: return 36;
case 0b11: return 54;
}
return 0;
}

View File

@ -1,31 +0,0 @@
#include "TMC2130Stepper.h"
#include "TMC2130Stepper_MACROS.h"
// COOLCONF
uint32_t TMC2130Stepper::COOLCONF() { return COOLCONF_sr; }
void TMC2130Stepper::COOLCONF(uint32_t input) {
COOLCONF_sr = input;
TMC_WRITE_REG(COOLCONF);
}
void TMC2130Stepper::semin( uint8_t B ) { TMC_MOD_REG(COOLCONF, SEMIN); }
void TMC2130Stepper::seup( uint8_t B ) { TMC_MOD_REG(COOLCONF, SEUP); }
void TMC2130Stepper::semax( uint8_t B ) { TMC_MOD_REG(COOLCONF, SEMAX); }
void TMC2130Stepper::sedn( uint8_t B ) { TMC_MOD_REG(COOLCONF, SEDN); }
void TMC2130Stepper::seimin( bool B ) { TMC_MOD_REG(COOLCONF, SEIMIN); }
void TMC2130Stepper::sgt( int8_t B ) { TMC_MOD_REG(COOLCONF, SGT); }
void TMC2130Stepper::sfilt( bool B ) { TMC_MOD_REG(COOLCONF, SFILT); }
uint8_t TMC2130Stepper::semin() { TMC_GET_BYTE(COOLCONF, SEMIN); }
uint8_t TMC2130Stepper::seup() { TMC_GET_BYTE(COOLCONF, SEUP); }
uint8_t TMC2130Stepper::semax() { TMC_GET_BYTE(COOLCONF, SEMAX); }
uint8_t TMC2130Stepper::sedn() { TMC_GET_BYTE(COOLCONF, SEDN); }
bool TMC2130Stepper::seimin() { TMC_GET_BYTE(COOLCONF, SEIMIN); }
//int8_t TMC2130Stepper::sgt() { TMC_GET_BYTE(COOLCONF, SGT); }
bool TMC2130Stepper::sfilt() { TMC_GET_BYTE(COOLCONF, SFILT); }
int8_t TMC2130Stepper::sgt() {
// Two's complement in a 7bit value
int8_t val = (COOLCONF()&SGT_bm) >> SGT_bp;
return val <= 63 ? val : val - 128;
}

View File

@ -1,29 +0,0 @@
#include "TMC2130Stepper.h"
#include "TMC2130Stepper_MACROS.h"
uint32_t TMC2130Stepper::DRV_STATUS() { TMC_READ_REG_R(DRV_STATUS); }
uint16_t TMC2130Stepper::sg_result(){ TMC_GET_BYTE_R(DRV_STATUS, SG_RESULT); }
bool TMC2130Stepper::fsactive() { TMC_GET_BYTE_R(DRV_STATUS, FSACTIVE); }
uint8_t TMC2130Stepper::cs_actual() { TMC_GET_BYTE_R(DRV_STATUS, CS_ACTUAL); }
bool TMC2130Stepper::stallguard() { TMC_GET_BYTE_R(DRV_STATUS, STALLGUARD); }
bool TMC2130Stepper::ot() { TMC_GET_BYTE_R(DRV_STATUS, OT); }
bool TMC2130Stepper::otpw() { TMC_GET_BYTE_R(DRV_STATUS, OTPW); }
bool TMC2130Stepper::s2ga() { TMC_GET_BYTE_R(DRV_STATUS, S2GA); }
bool TMC2130Stepper::s2gb() { TMC_GET_BYTE_R(DRV_STATUS, S2GB); }
bool TMC2130Stepper::ola() { TMC_GET_BYTE_R(DRV_STATUS, OLA); }
bool TMC2130Stepper::olb() { TMC_GET_BYTE_R(DRV_STATUS, OLB); }
bool TMC2130Stepper::stst() { TMC_GET_BYTE_R(DRV_STATUS, STST); }
/*
uint16_t TMC2130Stepper::sg_result() {
uint32_t drv_status = 0x00000000UL;
Serial.print("drv_status=");
Serial.print(drv_status);
drv_status = DRV_STATUS();
Serial.print("\tdrv_status=");
Serial.print(drv_status);
Serial.print("\t");
return drv_status&SG_RESULT_bm;
}
*/

View File

@ -1,54 +0,0 @@
#include "TMC2130Stepper.h"
#include "TMC2130Stepper_MACROS.h"
// GCONF
uint32_t TMC2130Stepper::GCONF() { TMC_READ_REG(GCONF); }
void TMC2130Stepper::GCONF(uint32_t input) {
GCONF_sr = input;
TMC_WRITE_REG(GCONF);
}
void TMC2130Stepper::I_scale_analog(bool B) { TMC_MOD_REG(GCONF, I_SCALE_ANALOG); }
void TMC2130Stepper::internal_Rsense(bool B) { TMC_MOD_REG(GCONF, INTERNAL_RSENSE); }
void TMC2130Stepper::en_pwm_mode(bool B) { TMC_MOD_REG(GCONF, EN_PWM_MODE); }
void TMC2130Stepper::enc_commutation(bool B) { TMC_MOD_REG(GCONF, ENC_COMMUTATION); }
void TMC2130Stepper::shaft(bool B) { TMC_MOD_REG(GCONF, SHAFT); }
void TMC2130Stepper::diag0_error(bool B) { TMC_MOD_REG(GCONF, DIAG0_ERROR); }
void TMC2130Stepper::diag0_otpw(bool B) { TMC_MOD_REG(GCONF, DIAG0_OTPW); }
void TMC2130Stepper::diag0_stall(bool B) { TMC_MOD_REG(GCONF, DIAG0_STALL); }
void TMC2130Stepper::diag1_stall(bool B) { TMC_MOD_REG(GCONF, DIAG1_STALL); }
void TMC2130Stepper::diag1_index(bool B) { TMC_MOD_REG(GCONF, DIAG1_INDEX); }
void TMC2130Stepper::diag1_onstate(bool B) { TMC_MOD_REG(GCONF, DIAG1_ONSTATE); }
void TMC2130Stepper::diag1_steps_skipped(bool B) { TMC_MOD_REG(GCONF, DIAG1_STEPS_SKIPPED); }
void TMC2130Stepper::diag0_int_pushpull(bool B) { TMC_MOD_REG(GCONF, DIAG0_INT_PUSHPULL); }
void TMC2130Stepper::diag1_pushpull(bool B) { TMC_MOD_REG(GCONF, DIAG1_PUSHPULL); }
void TMC2130Stepper::small_hysteresis(bool B) { TMC_MOD_REG(GCONF, SMALL_HYSTERESIS); }
void TMC2130Stepper::stop_enable(bool B) { TMC_MOD_REG(GCONF, STOP_ENABLE); }
void TMC2130Stepper::direct_mode(bool B) { TMC_MOD_REG(GCONF, DIRECT_MODE); }
bool TMC2130Stepper::I_scale_analog() { TMC_GET_BYTE(GCONF, I_SCALE_ANALOG); }
bool TMC2130Stepper::internal_Rsense() { TMC_GET_BYTE(GCONF, INTERNAL_RSENSE); }
bool TMC2130Stepper::en_pwm_mode() { TMC_GET_BYTE(GCONF, EN_PWM_MODE); }
bool TMC2130Stepper::enc_commutation() { TMC_GET_BYTE(GCONF, ENC_COMMUTATION); }
bool TMC2130Stepper::shaft() { TMC_GET_BYTE(GCONF, SHAFT); }
bool TMC2130Stepper::diag0_error() { TMC_GET_BYTE(GCONF, DIAG0_ERROR); }
bool TMC2130Stepper::diag0_otpw() { TMC_GET_BYTE(GCONF, DIAG0_OTPW); }
bool TMC2130Stepper::diag0_stall() { TMC_GET_BYTE(GCONF, DIAG0_STALL); }
bool TMC2130Stepper::diag1_stall() { TMC_GET_BYTE(GCONF, DIAG1_STALL); }
bool TMC2130Stepper::diag1_index() { TMC_GET_BYTE(GCONF, DIAG1_INDEX); }
bool TMC2130Stepper::diag1_onstate() { TMC_GET_BYTE(GCONF, DIAG1_ONSTATE); }
bool TMC2130Stepper::diag1_steps_skipped() { TMC_GET_BYTE(GCONF, DIAG1_STEPS_SKIPPED); }
bool TMC2130Stepper::diag0_int_pushpull() { TMC_GET_BYTE(GCONF, DIAG0_INT_PUSHPULL); }
bool TMC2130Stepper::diag1_pushpull() { TMC_GET_BYTE(GCONF, DIAG1_PUSHPULL); }
bool TMC2130Stepper::small_hysteresis() { TMC_GET_BYTE(GCONF, SMALL_HYSTERESIS); }
bool TMC2130Stepper::stop_enable() { TMC_GET_BYTE(GCONF, STOP_ENABLE); }
bool TMC2130Stepper::direct_mode() { TMC_GET_BYTE(GCONF, DIRECT_MODE); }
/*
bit 18 not implemented:
test_mode 0:
Normal operation 1:
Enable analog test output on pin DCO. IHOLD[1..0] selects the function of DCO:
02: T120, DAC, VDDH Attention:
Not for user, set to 0 for normal operation!
*/

View File

@ -1,16 +0,0 @@
#include "TMC2130Stepper.h"
#include "TMC2130Stepper_MACROS.h"
// IHOLD_IRUN
void TMC2130Stepper::IHOLD_IRUN(uint32_t input) {
IHOLD_IRUN_sr = input;
TMC_WRITE_REG(IHOLD_IRUN);
}
uint32_t TMC2130Stepper::IHOLD_IRUN() { return IHOLD_IRUN_sr; }
void TMC2130Stepper::ihold(uint8_t B) { TMC_MOD_REG(IHOLD_IRUN, IHOLD); }
void TMC2130Stepper::irun(uint8_t B) { TMC_MOD_REG(IHOLD_IRUN, IRUN); }
void TMC2130Stepper::iholddelay(uint8_t B) { TMC_MOD_REG(IHOLD_IRUN, IHOLDDELAY); }
uint8_t TMC2130Stepper::ihold() { TMC_GET_BYTE(IHOLD_IRUN, IHOLD); }
uint8_t TMC2130Stepper::irun() { TMC_GET_BYTE(IHOLD_IRUN, IRUN); }
uint8_t TMC2130Stepper::iholddelay() { TMC_GET_BYTE(IHOLD_IRUN, IHOLDDELAY); }

View File

@ -1,22 +0,0 @@
#ifndef TMC2130Stepper_MACROS_H
#define TMC2130Stepper_MACROS_H
#include "TMC2130Stepper.h"
#include "TMC2130Stepper_REGDEFS.h"
#define TMC_WRITE_REG(R) send2130(TMC2130_WRITE|REG_##R, &R##_sr);
#define TMC_READ_REG(R) send2130(TMC2130_READ|REG_##R, &R##_sr); return R##_sr
#define TMC_READ_REG_R(R) tmp_sr=0; send2130(TMC2130_READ|REG_##R, &tmp_sr); return tmp_sr;
#define TMC_MOD_REG(REG, SETTING) REG##_sr &= ~SETTING##_bm; \
REG##_sr |= ((uint32_t)B<<SETTING##_bp)&SETTING##_bm; \
TMC_WRITE_REG(REG);
#define TMC_GET_BYTE(REG, SETTING) return (REG()&SETTING##_bm) >> SETTING##_bp;
#define TMC_GET_BYTE_R(REG, SETTING) return (REG()&SETTING##_bm) >> SETTING##_bp;
#define TMC_GET_BIT(REG, SETTING) return (bool)((REG()&SETTING##_bm) >> SETTING##_bp);
#endif

View File

@ -1,24 +0,0 @@
#include "TMC2130Stepper.h"
#include "TMC2130Stepper_MACROS.h"
// PWMCONF
uint32_t TMC2130Stepper::PWMCONF() { return PWMCONF_sr; }
void TMC2130Stepper::PWMCONF(uint32_t input) {
PWMCONF_sr = input;
TMC_WRITE_REG(PWMCONF);
}
void TMC2130Stepper::pwm_ampl( uint8_t B ) { TMC_MOD_REG(PWMCONF, PWM_AMPL); }
void TMC2130Stepper::pwm_grad( uint8_t B ) { TMC_MOD_REG(PWMCONF, PWM_GRAD); }
void TMC2130Stepper::pwm_freq( uint8_t B ) { TMC_MOD_REG(PWMCONF, PWM_FREQ); }
void TMC2130Stepper::pwm_autoscale( bool B ) { TMC_MOD_REG(PWMCONF, PWM_AUTOSCALE); }
void TMC2130Stepper::pwm_symmetric( bool B ) { TMC_MOD_REG(PWMCONF, PWM_SYMMETRIC); }
void TMC2130Stepper::freewheel( uint8_t B ) { TMC_MOD_REG(PWMCONF, FREEWHEEL); }
uint8_t TMC2130Stepper::pwm_ampl() { TMC_GET_BYTE(PWMCONF, PWM_AMPL); }
uint8_t TMC2130Stepper::pwm_grad() { TMC_GET_BYTE(PWMCONF, PWM_GRAD); }
uint8_t TMC2130Stepper::pwm_freq() { TMC_GET_BYTE(PWMCONF, PWM_FREQ); }
bool TMC2130Stepper::pwm_autoscale() { TMC_GET_BYTE(PWMCONF, PWM_AUTOSCALE); }
bool TMC2130Stepper::pwm_symmetric() { TMC_GET_BYTE(PWMCONF, PWM_SYMMETRIC); }
uint8_t TMC2130Stepper::freewheel() { TMC_GET_BYTE(PWMCONF, FREEWHEEL); }

View File

@ -1,288 +0,0 @@
#ifndef TMC2130Stepper_REGDEFS_h
#define TMC2130Stepper_REGDEFS_h
constexpr uint8_t TMC2130_READ = 0x00;
constexpr uint8_t TMC2130_WRITE = 0x80;
// Register memory positions
constexpr uint8_t REG_GCONF = 0x00;
constexpr uint8_t REG_GSTAT = 0x01;
constexpr uint8_t REG_IOIN = 0x04;
constexpr uint8_t REG_IHOLD_IRUN = 0x10;
constexpr uint8_t REG_TPOWERDOWN = 0x11;
constexpr uint8_t REG_TSTEP = 0x12;
constexpr uint8_t REG_TPWMTHRS = 0x13;
constexpr uint8_t REG_TCOOLTHRS = 0x14;
constexpr uint8_t REG_THIGH = 0x15;
constexpr uint8_t REG_XDIRECT = 0x2D;
constexpr uint8_t REG_VDCMIN = 0x33;
constexpr uint8_t REG_MSLUT0 = 0x60;
constexpr uint8_t REG_MSLUT1 = 0x61;
constexpr uint8_t REG_MSLUT2 = 0x62;
constexpr uint8_t REG_MSLUT3 = 0x63;
constexpr uint8_t REG_MSLUT4 = 0x64;
constexpr uint8_t REG_MSLUT5 = 0x65;
constexpr uint8_t REG_MSLUT6 = 0x66;
constexpr uint8_t REG_MSLUT7 = 0x67;
constexpr uint8_t REG_MSLUTSEL = 0x68;
constexpr uint8_t REG_MSLUTSTART = 0x69;
constexpr uint8_t REG_MSCNT = 0x6A;
constexpr uint8_t REG_MSCURACT = 0x6B;
constexpr uint8_t REG_CHOPCONF = 0x6C;
constexpr uint8_t REG_COOLCONF = 0x6D;
constexpr uint8_t REG_DCCTRL = 0x6E;
constexpr uint8_t REG_DRV_STATUS = 0x6F;
constexpr uint8_t REG_PWMCONF = 0x70;
constexpr uint8_t REG_PWM_SCALE = 0x71;
constexpr uint8_t REG_ENCM_CTRL = 0x72;
constexpr uint8_t REG_LOST_STEPS = 0x73;
// SPI_STATUS
constexpr uint8_t RESET_FLAG_bp = 0;
constexpr uint8_t DRIVER_ERROR_bp = 1;
constexpr uint8_t SG2_bp = 2;
constexpr uint8_t STANDSTILL_bp = 3;
constexpr uint32_t RESET_FLAG_bm = 0x1UL;
constexpr uint32_t DRIVER_ERROR_bm = 0x2UL;
constexpr uint32_t SG2_bm = 0x4UL;
constexpr uint32_t STANDSTILL_bm = 0x8UL;
// GCONF
constexpr uint8_t I_SCALE_ANALOG_bp = 0;
constexpr uint8_t INTERNAL_RSENSE_bp = 1;
constexpr uint8_t EN_PWM_MODE_bp = 2;
constexpr uint8_t ENC_COMMUTATION_bp = 3;
constexpr uint8_t SHAFT_bp = 4;
constexpr uint8_t DIAG0_ERROR_bp = 5;
constexpr uint8_t DIAG0_OTPW_bp = 6;
constexpr uint8_t DIAG0_STALL_bp = 7;
constexpr uint8_t DIAG1_STALL_bp = 8;
constexpr uint8_t DIAG1_INDEX_bp = 9;
constexpr uint8_t DIAG1_ONSTATE_bp = 10;
constexpr uint8_t DIAG1_STEPS_SKIPPED_bp = 11;
constexpr uint8_t DIAG0_INT_PUSHPULL_bp = 12;
constexpr uint8_t DIAG1_PUSHPULL_bp = 13;
constexpr uint8_t SMALL_HYSTERESIS_bp = 14;
constexpr uint8_t STOP_ENABLE_bp = 15;
constexpr uint8_t DIRECT_MODE_bp = 16;
constexpr uint32_t GCONF_bm = 0x3FFFFUL;
constexpr uint32_t I_SCALE_ANALOG_bm = 0x1UL;
constexpr uint32_t INTERNAL_RSENSE_bm = 0x2UL;
constexpr uint32_t EN_PWM_MODE_bm = 0x4UL;
constexpr uint32_t ENC_COMMUTATION_bm = 0x8UL;
constexpr uint32_t SHAFT_bm = 0x10UL;
constexpr uint32_t DIAG0_ERROR_bm = 0x20UL;
constexpr uint32_t DIAG0_OTPW_bm = 0x40UL;
constexpr uint32_t DIAG0_STALL_bm = 0x80UL;
constexpr uint32_t DIAG1_STALL_bm = 0x100UL;
constexpr uint32_t DIAG1_INDEX_bm = 0x200UL;
constexpr uint32_t DIAG1_ONSTATE_bm = 0x400UL;
constexpr uint32_t DIAG1_STEPS_SKIPPED_bm = 0x800UL;
constexpr uint32_t DIAG0_INT_PUSHPULL_bm = 0x1000UL;
constexpr uint32_t DIAG1_PUSHPULL_bm = 0x2000UL;
constexpr uint32_t SMALL_HYSTERESIS_bm = 0x4000UL;
constexpr uint32_t STOP_ENABLE_bm = 0x8000UL;
constexpr uint32_t DIRECT_MODE_bm = 0x10000UL;
// GSTAT
constexpr uint8_t RESET_bp = 0;
constexpr uint8_t DRV_ERR_bp = 1;
constexpr uint8_t UV_CP_bp = 2;
constexpr uint32_t GSTAT_bm = 0x7UL;
constexpr uint32_t RESET_bm = 0b1UL;
constexpr uint32_t DRV_ERR_bm = 0b10UL;
constexpr uint32_t UV_CP_bm = 0b100UL;
// IOIN
constexpr uint8_t STEP_bp = 0;
constexpr uint8_t DIR_bp = 1;
constexpr uint8_t DCEN_CFG4_bp = 2;
constexpr uint8_t DCIN_CFG5_bp = 3;
constexpr uint8_t DRV_ENN_CFG6_bp = 4;
constexpr uint8_t DCO_bp = 5;
constexpr uint8_t VERSION_bp = 24;
constexpr uint32_t IOIN_bm = 0xFF00003FUL;
constexpr uint32_t STEP_bm = 0x1UL;
constexpr uint32_t DIR_bm = 0x2UL;
constexpr uint32_t DCEN_CFG4_bm = 0x4UL;
constexpr uint32_t DCIN_CFG5_bm = 0x8UL;
constexpr uint32_t DRV_ENN_CFG6_bm = 0x10UL;
constexpr uint32_t DCO_bm = 0x20UL;
constexpr uint32_t VERSION_bm = 0xFF000000UL;
// IHOLD_IRUN
constexpr uint8_t IHOLD_bp = 0;
constexpr uint8_t IRUN_bp = 8;
constexpr uint8_t IHOLDDELAY_bp = 16;
constexpr uint32_t IHOLD_IRUN_bm = 0xF1F1FUL;
constexpr uint32_t IHOLD_bm = 0x1FUL;
constexpr uint32_t IRUN_bm = 0x1F00UL;
constexpr uint32_t IHOLDDELAY_bm = 0xF0000UL;
// TPOWERDOWN
constexpr uint8_t TPOWERDOWN_bp = 0;
constexpr uint32_t TPOWERDOWN_bm = 0xFFUL;
// TSTEP
constexpr uint8_t TSTEP_bp = 0;
constexpr uint32_t TSTEP_bm = 0xFFFFFUL;
// TPWMTHRS
constexpr uint8_t TPWMTHRS_bp = 0;
constexpr uint32_t TPWMTHRS_bm = 0xFFFFFUL;
// TCOOLTHRS
constexpr uint8_t TCOOLTHRS_bp = 0;
constexpr uint32_t TCOOLTHRS_bm = 0xFFFFFUL;
// THIGH
constexpr uint8_t THIGH_bp = 0;
constexpr uint32_t THIGH_bm = 0xFFFFFUL;
// XDIRECT
constexpr uint8_t XDIRECT_bp = 0;
constexpr uint32_t XDIRECT_bm = 0xFFFFFFFFUL;
constexpr uint8_t COIL_A_bp = 0;
constexpr uint8_t COIL_B_bp = 16;
constexpr uint32_t COIL_A_bm = 0x1FFUL;
constexpr uint32_t COIL_B_bm = 0x1FF0000UL;
// VDCMIN
constexpr uint8_t VDCMIN_bp = 0;
constexpr uint32_t VDCMIN_bm = 0x7FFFFFUL;
// MSLUT0
constexpr uint8_t MSLUT0_bp = 0;
constexpr uint32_t MSLUT0_bm = 0xFFFFFFFFUL;
// MSLUT1
constexpr uint8_t MSLUT1_bp = 0;
constexpr uint32_t MSLUT1_bm = 0xFFFFFFFFUL;
// MSLUT2
constexpr uint8_t MSLUT2_bp = 0;
constexpr uint32_t MSLUT2_bm = 0xFFFFFFFFUL;
// MSLUT3
constexpr uint8_t MSLUT3_bp = 0;
constexpr uint32_t MSLUT3_bm = 0xFFFFFFFFUL;
// MSLUT4
constexpr uint8_t MSLUT4_bp = 0;
constexpr uint32_t MSLUT4_bm = 0xFFFFFFFFUL;
// MSLUT5
constexpr uint8_t MSLUT5_bp = 0;
constexpr uint32_t MSLUT5_bm = 0xFFFFFFFFUL;
// MSLUT6
constexpr uint8_t MSLUT6_bp = 0;
constexpr uint32_t MSLUT6_bm = 0xFFFFFFFFUL;
// MSLUT7
constexpr uint8_t MSLUT7_bp = 0;
constexpr uint32_t MSLUT7_bm = 0xFFFFFFFFUL;
// MSLUTSEL
constexpr uint8_t MSLUTSEL_bp = 0;
constexpr uint32_t MSLUTSEL_bm = 0xFFFFFFFFUL;
// MSLUTSTART
constexpr uint8_t START_SIN_bp = 0;
constexpr uint8_t START_SIN90_bp = 16;
constexpr uint32_t START_SIN_bm = 0xFFUL;
constexpr uint32_t START_SIN90_bm = 0xFF0000UL;
// MSCNT
constexpr uint8_t MSCNT_bp = 0;
constexpr uint32_t MSCNT_bm = 0x3FFUL;
// MSCURACT
constexpr uint8_t CUR_A_bp = 0;
constexpr uint8_t CUR_B_bp = 16;
constexpr uint32_t CUR_A_bm = 0x1FFUL;
constexpr uint32_t CUR_B_bm = 0x1FF0000UL;
// CHOPCONF
constexpr uint8_t TOFF_bp = 0;
constexpr uint8_t HSTRT_bp = 4;
constexpr uint8_t FD_bp = 4;
constexpr uint8_t HEND_bp = 7;
constexpr uint8_t DISFDCC_bp = 12;
constexpr uint8_t RNDTF_bp = 13;
constexpr uint8_t CHM_bp = 14;
constexpr uint8_t TBL_bp = 15;
constexpr uint8_t VSENSE_bp = 17;
constexpr uint8_t VHIGHFS_bp = 18;
constexpr uint8_t VHIGHCHM_bp = 19;
constexpr uint8_t SYNC_bp = 20;
constexpr uint8_t MRES_bp = 24;
constexpr uint8_t INTPOL_bp = 28;
constexpr uint8_t DEDGE_bp = 29;
constexpr uint8_t DISS2G_bp = 30;
constexpr uint32_t CHOPCONF_bm = 0xFFFFFFFFUL;
constexpr uint32_t TOFF_bm = 0xFUL;
constexpr uint32_t HSTRT_bm = 0x70UL;
constexpr uint32_t FD_bm = 0x830UL;
constexpr uint32_t HEND_bm = 0x780UL;
constexpr uint32_t DISFDCC_bm = 0x1000UL;
constexpr uint32_t RNDTF_bm = 0x2000UL;
constexpr uint32_t CHM_bm = 0x4000UL;
constexpr uint32_t TBL_bm = 0x18000UL;
constexpr uint32_t VSENSE_bm = 0x20000UL;
constexpr uint32_t VHIGHFS_bm = 0x40000UL;
constexpr uint32_t VHIGHCHM_bm = 0x80000UL;
constexpr uint32_t SYNC_bm = 0xF00000UL;
constexpr uint32_t MRES_bm = 0xF000000UL;
constexpr uint32_t INTPOL_bm = 0x10000000UL;
constexpr uint32_t DEDGE_bm = 0x20000000UL;
constexpr uint32_t DISS2G_bm = 0x40000000UL;
// COOLCONF
constexpr uint8_t SEMIN_bp = 0;
constexpr uint8_t SEUP_bp = 5;
constexpr uint8_t SEMAX_bp = 8;
constexpr uint8_t SEDN_bp = 13;
constexpr uint8_t SEIMIN_bp = 15;
constexpr uint8_t SGT_bp = 16;
constexpr uint8_t SFILT_bp = 24;
constexpr uint32_t COOLCONF_bm = 0x3FFFFFFUL;
constexpr uint32_t SEMIN_bm = 0xFUL;
constexpr uint32_t SEUP_bm = 0x60UL;
constexpr uint32_t SEMAX_bm = 0xF00UL;
constexpr uint32_t SEDN_bm = 0x6000UL;
constexpr uint32_t SEIMIN_bm = 0x8000UL;
constexpr uint32_t SGT_bm = 0x7F0000UL;
constexpr uint32_t SFILT_bm = 0x1000000UL;
// DCCTRL
constexpr uint8_t DC_TIME_bp = 0;
constexpr uint8_t DC_SG_bp = 16;
constexpr uint32_t DC_TIME_bm = 0x3FFUL;
constexpr uint32_t DC_SG_bm = 0xFF0000UL;
// DRV_STATUS
constexpr uint8_t SG_RESULT_bp = 0;
constexpr uint8_t FSACTIVE_bp = 15;
constexpr uint8_t CS_ACTUAL_bp = 16;
constexpr uint8_t STALLGUARD_bp = 24;
constexpr uint8_t OT_bp = 25;
constexpr uint8_t OTPW_bp = 26;
constexpr uint8_t S2GA_bp = 27;
constexpr uint8_t S2GB_bp = 28;
constexpr uint8_t OLA_bp = 29;
constexpr uint8_t OLB_bp = 30;
constexpr uint8_t STST_bp = 31;
constexpr uint32_t DRV_STATUS_bm = 0xFFFFFFFFUL;
constexpr uint32_t SG_RESULT_bm = 0x3FFUL;
constexpr uint32_t FSACTIVE_bm = 0x8000UL;
constexpr uint32_t CS_ACTUAL_bm = 0x1F0000UL;
constexpr uint32_t STALLGUARD_bm = 0x1000000UL;
constexpr uint32_t OT_bm = 0x2000000UL;
constexpr uint32_t OTPW_bm = 0x4000000UL;
constexpr uint32_t S2GA_bm = 0x8000000UL;
constexpr uint32_t S2GB_bm = 0x10000000UL;
constexpr uint32_t OLA_bm = 0x20000000UL;
constexpr uint32_t OLB_bm = 0x40000000UL;
constexpr uint32_t STST_bm = 0x80000000UL;
// PWMCONF
constexpr uint8_t PWM_AMPL_bp = 0;
constexpr uint8_t PWM_GRAD_bp = 8;
constexpr uint8_t PWM_FREQ_bp = 16;
constexpr uint8_t PWM_AUTOSCALE_bp = 18;
constexpr uint8_t PWM_SYMMETRIC_bp = 19;
constexpr uint8_t FREEWHEEL_bp = 20;
constexpr uint32_t PWMCONF_bm = 0x7FFFFFUL;
constexpr uint32_t PWM_AMPL_bm = 0xFFUL;
constexpr uint32_t PWM_GRAD_bm = 0xFF00UL;
constexpr uint32_t PWM_FREQ_bm = 0x30000UL;
constexpr uint32_t PWM_AUTOSCALE_bm = 0x40000UL;
constexpr uint32_t PWM_SYMMETRIC_bm = 0x80000UL;
constexpr uint32_t FREEWHEEL_bm = 0x300000UL;
// PWM_SCALE
constexpr uint8_t PWM_SCALE_bp = 0;
constexpr uint32_t PWM_SCALE_bm = 0xFFUL;
// ENCM_CTRL
constexpr uint8_t INV_bp = 0;
constexpr uint8_t MAXSPEED_bp = 1;
constexpr uint32_t INV_bm = 0x1UL;
constexpr uint32_t MAXSPEED_bm = 0x2UL;
// LOST_STEPS
constexpr uint8_t LOST_STEPS_bp = 0;
constexpr uint32_t LOST_STEPS_bm = 0xFFFFFUL;
#endif

View File

@ -1,33 +0,0 @@
#ifndef TMC2130Stepper_UTILITY_h
#define TMC2130Stepper_UTILITY_h
void print_HEX(uint32_t data) {
for(uint8_t B=24; B>=4; B-=8){
Serial.print((data>>(B+4))&0xF, HEX);
Serial.print((data>>B)&0xF, HEX);
Serial.print(":");
}
Serial.print((data>>4)&0xF, HEX);
Serial.print(data&0xF, HEX);
}
void print_BIN(uint32_t data) {
int b = 31;
for(; b>=24; b--){
Serial.print((data>>b)&0b1);
}
Serial.print(".");
for(; b>=16; b--){
Serial.print((data>>b)&0b1);
}
Serial.print(".");
for(; b>=8; b--){
Serial.print((data>>b)&0b1);
}
Serial.print(".");
for(; b>=0; b--){
Serial.print((data>>b)&0b1);
}
}
#endif

View File

@ -0,0 +1,132 @@
#include "TMC2130_Basics.h"
TMC2130_Basics::TMC2130_Basics(uint8_t csPin)
{
_csPin = csPin;
_status = 0;
_debug = "";
}
// initialize the driver with its CS/SS pin
void TMC2130_Basics::init() {
pinMode(_csPin, OUTPUT);
digitalWrite(_csPin, HIGH);
init_SPI();
read_STAT();
}
// initialize SPI
void TMC2130_Basics::init_SPI() {
SPI.setDataMode(FB_TMC_SPI_DATA_MODE);
SPI.setBitOrder(FB_TMC_SPI_BIT_ORDER);
SPI.setClockDivider(FB_TMC_SPI_CLOCK_DIVIDER);
SPI.begin();
}
// read status
uint8_t TMC2130_Basics::read_STAT()
{
init_SPI();
digitalWrite(_csPin, LOW);
// read address
_status = SPI.transfer(0x00);
// flush 4 bytes
for (int i = 0; i < 4; i++) {
SPI.transfer(0x00);
}
digitalWrite(_csPin, HIGH);
return _status;
}
// read a register
uint8_t TMC2130_Basics::read_REG(uint8_t address, uint32_t *data)
{
init_SPI();
digitalWrite(_csPin, LOW);
// read address
_status = SPI.transfer(address&~FB_TMC_WRITE);
// flush 4 bytes
for (int i = 0; i < 4; i++) {
SPI.transfer(0x00);
}
digitalWrite(_csPin, HIGH);
// restart transmission
digitalWrite(_csPin, LOW);
// read address
_status = SPI.transfer(address&~FB_TMC_WRITE);
// retrieve data
*data = SPI.transfer(0x00) & 0xFF;
*data <<= 8;
*data |= SPI.transfer(0x00) & 0xFF;
*data <<= 8;
*data |= SPI.transfer(0x00) & 0xFF;
*data <<= 8;
*data |= SPI.transfer(0x00) & 0xFF;
digitalWrite(_csPin, HIGH);
return _status;
}
// write to a register
uint8_t TMC2130_Basics::write_REG(uint8_t address, uint32_t data)
{
digitalWrite(_csPin, LOW);
// write address
_status = SPI.transfer(address | FB_TMC_WRITE);
// write data
SPI.transfer((data >> 24UL) & 0xFF);
SPI.transfer((data >> 16UL) & 0xFF);
SPI.transfer((data >> 8UL) & 0xFF);
SPI.transfer((data >> 0UL) & 0xFF);
digitalWrite(_csPin, HIGH);
return _status;
}
// alter a register using a bitmask
uint8_t TMC2130_Basics::alter_REG(uint8_t address, uint32_t data, uint32_t mask)
{
uint32_t oldData, newData;
read_REG(address, &oldData);
newData = (oldData&~mask) | (data&mask);
write_REG(address, newData);
return _status;
}
// set single bits in the GCONF register
uint8_t TMC2130_Basics::set_GCONF(uint8_t position, uint8_t value)
{
alter_REG(FB_TMC_REG_GCONF, uint32_t(value) << position, 0x1UL << position);
return _status;
}
// set single bits or values in the chopconf register (constraining masks are applied if necessary)
uint8_t TMC2130_Basics::set_CHOPCONF(uint8_t position, uint8_t value)
{
alter_REG(FB_TMC_REG_CHOPCONF, uint32_t(value) << position, FB_TMC_CHOPCONF_MASKS[position] << position);
return _status;
}
uint8_t TMC2130_Basics::getStatus()
{
return _status;
}

View File

@ -0,0 +1,47 @@
// TMC2130_Basics.h
#ifndef _TMC2130_BASICS_h
#define _TMC2130_BASICS_h
#if defined(ARDUINO) && ARDUINO >= 100
#include "arduino.h"
#else
#include "WProgram.h"
#endif
#include "TMC2130_Basics_Reg.h"
class TMC2130_Basics {
public:
TMC2130_Basics(uint8_t csPin);
void init();
void init_SPI();
uint8_t read_STAT();
uint8_t read_REG(uint8_t address, uint32_t *data);
uint8_t write_REG(uint8_t address, uint32_t data);
uint8_t alter_REG(uint8_t address, uint32_t data, uint32_t mask);
uint8_t set_GCONF(uint8_t bit, uint8_t value);
uint8_t set_CHOPCONF(uint8_t position, uint8_t value);
uint8_t getStatus();
//boolean isReset();
//boolean isError();
//boolean isStallguard();
//boolean isStandstill();
//String debug();
private:
uint32_t _coolconf;
uint32_t _pwmconf;
uint8_t _csPin;
uint8_t _status;
String _debug;
};
#endif

View File

@ -0,0 +1,305 @@
#ifndef TMC2130_BASICS_REG_H
#define TMC2130_BASICS_REG_H
#if ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#include <SPI.h>
// SPI
#define FB_TMC_SPI_CLOCK_DIVIDER SPI_CLOCK_DIV8
#define FB_TMC_SPI_DATA_MODE SPI_MODE3
#define FB_TMC_SPI_BIT_ORDER MSBFIRST
// RW
#define FB_TMC_READ (0x00)
#define FB_TMC_WRITE (0x80)
// SPISTATUS MASKS
#define FB_TMC_SPISTATUS_RESET_MASK (0x01)
#define FB_TMC_SPISTATUS_ERROR_MASK (0x02)
#define FB_TMC_SPISTATUS_STALLGUARD_MASK (0x04)
#define FB_TMC_SPISTATUS_STANDSTILL_MASK (0x08)
// REGISTERS
#define FB_TMC_REG_GCONF (0x00) // RW // 17 // Global configuration flags
#define FB_TMC_REG_GSTAT (0x01) // RC // 3 // Global status flags
#define FB_TMC_REG_IOIN (0x04) // R // 8+8 // Reads the state of all input pins available
#define FB_TMC_REG_IHOLD_IRUN (0x10) // W // 5+5+4 // Driver current control
#define FB_TMC_REG_TPOWERDOWN (0x11) // W // 8 // sets delay time after stand still (stst) to motor current power down (0-4 seconds) 0_((2^8)-1) * 2^18 tclk
#define FB_TMC_REG_TSTEP (0x12) // R // 20 // Actual measured time between two 1/256 microsteps derived from the step input frequency in units of 1/fCLK. Measured value is (2^20)-1 in case of overflow or stand still
#define FB_TMC_REG_TPWMTHRS (0x13) // W // 20 // Upper velocity threshold for stealthChop voltage PWM mode
#define FB_TMC_REG_TCOOLTHRS (0x14) // W // 20 // Lower threshold velocity for switching on smart energy coolStep and stallGuard feature (unsigned)
#define FB_TMC_REG_THIGH (0x15) // W // 20 // Velocity dependend switching into different chopper mode and fullstepping to maximize torque (unsigned)
#define FB_TMC_REG_XDIRECT (0x2D) // RW // 32 // specifies motor coil currents and polarity directly programmed via SPI. Use signed, two's complement numbers. In this mode, the current is scaled by IHOLD. Velocity based current regulation of voltage PWM is not available in this mode. +- 255 for both coils
#define FB_TMC_REG_VDCMIN (0x33) // W // 23 // automatic commutation dcStep becomes enabled by the external signal DCEN. VDCMIN is used as the minimum step velocity when the motor is heavily loaded. Hint: Also set DCCTRL parameters in order to operate dcStep
#define FB_TMC_REG_MSLUT0 (0x60) // W // 32 // Each bit gives the difference between entry x and entry x+1 when combined with the corresponding MSLUTSEL W bits. Differential coding for the first quarter of a wave. Start values for CUR_A and CUR_B are stored for MSCNT position 0 in START_SIN and START_SIN90.
#define FB_TMC_REG_MSLUT1 (0x61) // W // 32 //
#define FB_TMC_REG_MSLUT2 (0x62) // W // 32 //
#define FB_TMC_REG_MSLUT3 (0x63) // W // 32 //
#define FB_TMC_REG_MSLUT4 (0x64) // W // 32 //
#define FB_TMC_REG_MSLUT5 (0x65) // W // 32 //
#define FB_TMC_REG_MSLUT6 (0x66) // W // 32 //
#define FB_TMC_REG_MSLUT7 (0x67) // W // 32 //
#define FB_TMC_REG_MSLUTSEL (0x68) // W // 32 // defines four segments within each quarter MSLUT wave. Four 2 bit entries determine the meaning of a 0 and a 1 bit in the corresponding segment of MSLUT
#define FB_TMC_REG_MSLUTSTART (0x69) // W // 8+8 //
#define FB_TMC_REG_MSCNT (0x6A) // R // 10 //
#define FB_TMC_REG_MSCURACT (0x6B) // R // 9+9 //
#define FB_TMC_REG_CHOPCONF (0x6C) // RW // 32 //
#define FB_TMC_REG_COOLCONF (0x6D) // W // 25 //
#define FB_TMC_REG_DCCTRL (0x6E) // W // 24 //
#define FB_TMC_REG_DRV_STATUS (0x6F) // R // 22 //
#define FB_TMC_REG_PWMCONF (0x70) // W // 8 //
#define FB_TMC_REG_PWM_SCALE (0x71) // R // 8 //
#define FB_TMC_REG_ENCM_CTRL (0x72) // W // 2 //
#define FB_TMC_REG_LOST_STEPS (0x73) // R // 20 //
// GCONF OFFSETS
// for shifting incoming values to the right register position
#define FB_TMC_GCONF_I_SCALE_ANALOG (0) // 0: Internal, 1: AIN
#define FB_TMC_GCONF_INTERNAL_RSENSE (1) // 0: Normal, 1: Internal
#define FB_TMC_GCONF_EN_PWM_MODE (2) // 0: Disable, 1: Enable
#define FB_TMC_GCONF_ENC_COMMUTATION (3) // 0: Disable, 1: Enable
#define FB_TMC_GCONF_SHAFT (4) // 0: Normal, 1: Invert
#define FB_TMC_GCONF_DIAG0_ERROR (5) // 0: Disable, 1: Enable
#define FB_TMC_GCONF_DIAG0_OTPW (6) // 0: Disable, 1: Enable
#define FB_TMC_GCONF_DIAG0_STALL (7) // 0: Disable, 1: Enable
#define FB_TMC_GCONF_DIAG1_STALL (8) // 0: Disable, 1: Enable
#define FB_TMC_GCONF_DIAG1_INDEX (9) // 0: Disable, 1: Enable
#define FB_TMC_GCONF_DIAG1_ONSTATE (10) // 0: Disable, 1: Enable
#define FB_TMC_GCONF_DIAG1_STEPS_SKIPPED (11) // 0: Disable, 1: Enable
#define FB_TMC_GCONF_DIAG0_INT_PUSHPULL (12) // 0: Open Collector, 1: Push Pull
#define FB_TMC_GCONF_DIAG1_INT_PUSHPULL (13) // 0: Open Collector, 1: Push Pull
#define FB_TMC_GCONF_SMALL_HYSTERESIS (14) // 0: 1/16, 1: 1/32
#define FB_TMC_GCONF_STOP_ENABLE (15) // 0: Normal, 1: Emergency Stop
#define FB_TMC_GCONF_DIRECT_MODE (16) // 0: Normal, 1: XDIRECT
#define FB_TMC_GCONF_TEST_MODE (17) // 0: Normal, 1: Enable, Don't use!
// GCONF MASKS
// not required, all 1 bit
// IHOLD_IRUN OFFSETS
// for shifting incoming values to the right register position
#define FB_TMC_IHOLD (0)
#define FB_TMC_IRUN (8)
#define FB_TMC_IHOLDDELAY (16)
// IHOLD IRUN MASKS
#define FB_TMC_IHOLD_MASK (0b11111UL)
#define FB_TMC_IRUN_MASK (0b11111UL)
#define FB_TMC_IHOLDDELAY_MASK (0b1111UL)
// TPOWERDOWN
// no offsets required
#define FB_TMC_TPOWERDOWN_MASK (0b11111111UL)
// TSTEP
// no offsets required
#define FB_TMC_TSTEP_MASK (0b11111111111111111111UL)
// TPWMTHRS
// no offsets required
#define FB_TMC_TPWMTHRS_MASK (0b11111111111111111111UL)
// TCOOLTHRS
#define FB_TMC_TCOOLTHRS_MASK (0b11111111111111111111UL)
// THIGH
// no offsets required
#define FB_TMC_THIGH_MASK (0b11111111111111111111UL)
// XDIRECT OFFSETS
// for shifting incoming values to the right register position
#define FB_TMC_XDIRECT_COIL_A (0)
#define FB_TMC_XDIRECT_COIL_B (16)
// XDIRECT MASKS
// mask the bits from the values we want to set
#define FB_TMC_XDIRECT_MASK (0xFFFFFFFFUL)
#define FB_TMC_XDIRECT_COIL_A_MASK (0xFFFFUL)
#define FB_TMC_XDIRECT_COIL_B_MASK (0xFFFFUL)
// no offsets required
// needs no mask
// VDCMIN
// no offsets required
#define FB_TMC_VDCMIN_MASK (0b11111111111111111111111UL)
// MSLUT
// no offsets required
// needs no mask
// MSLUTSEL
// no offsets required
// needs no mask
// MSLUTSTART OFFSETS
#define FB_TMC_MSLUTSTART_START_SIN (0)
#define FB_TMC_MSLUTSTART_START_SIN90 (8)
// MSLUTSTART MASKS
#define FB_TMC_MSLUTSTART_MASK (0xFFFFUL)
#define FB_TMC_MSLUTSTART_START_SIN_MASK (0xFF)
#define FB_TMC_MSLUTSTART_START_SIN90_MASK (0xFF)
// MSCNT
// no offsets required
#define FB_TMC_MSCNT_MASK (0b1111111111)
// MSCURACT
// no offsets required
#define FB_TMC_MSCURACT_MASK (0b111111111111111111UL)
// CHOPCONF MASKS
// mask the bits from the values we want to set
const uint32_t FB_TMC_CHOPCONF_MASKS[] = {
0b1111UL, // 0 TOFF
0b111UL, // 1
0b11UL, // 2
0b1UL, // 3
0b111UL, // 4 HYSTERESIS_START
0b11UL, // 5
0b1UL, // 6
0b0001UL, // 7 HYSTERESIS_LOW
0b001UL, // 8
0b01UL, // 9
0b1UL, // 10
0b1UL, // 11 FAST_DECAY_TIMING
0b1UL, // 12 FAST_DECAY_MODE
0b1UL, // 13 RANDOM_TOFF
0b1UL, // 14 CHOPPER_MODE
0b11UL, // 15 TBL
0b1UL, // 16
0b1UL, // 17 SENSE_CURRENT_SCALING
0b1UL, // 18 HIGH_VELOCITY_STEPS
0b1UL, // 19 HIGH_VELOCITY_CHOPPER
0b1111UL, // 20 SYNC_PWM
0b111UL, // 21
0b11UL, // 22
0b1UL, // 23
0b1111UL, // 24 MRES
0b111UL, // 25
0b11UL, // 26
0b1UL, // 27
0b1UL, // 28 INTERPOLATE
0b1UL, // 29 DOUBLE_EDGE_PULSES
0b1UL, // 30 SHORT_PROTECTION
0b1UL // 31
};
// CHOPCONF OFFSETS
// for shifting incoming values to the right register position
#define FB_TMC_CHOPCONF_DISS2G (30)
#define FB_TMC_CHOPCONF_DEDGE (29)
#define FB_TMC_CHOPCONF_INTPOL (28)
#define FB_TMC_CHOPCONF_MRES (24)
#define FB_TMC_CHOPCONF_SYNC (20)
#define FB_TMC_CHOPCONF_VHIGHCHM (19)
#define FB_TMC_CHOPCONF_VHIGHFS (18)
#define FB_TMC_CHOPCONF_VSENSE (17)
#define FB_TMC_CHOPCONF_TBL (15)
#define FB_TMC_CHOPCONF_CHM (14)
#define FB_TMC_CHOPCONF_RNDTF (13)
#define FB_TMC_CHOPCONF_DISFDCC (12)
#define FB_TMC_CHOPCONF_FD (11)
#define FB_TMC_CHOPCONF_HEND (7)
#define FB_TMC_CHOPCONF_HSTRT (4)
#define FB_TMC_CHOPCONF_TOFF (0)
// COOLCONF BIT OFFSETS
// for shifting incoming values to the right register position
#define FB_TMC_COOLCONF_SFILT (24)
#define FB_TMC_COOLCONF_SGT (16)
#define FB_TMC_COOLCONF_SEIMIN (15)
#define FB_TMC_COOLCONF_SEDN (13)
#define FB_TMC_COOLCONF_SEMAX (8)
#define FB_TMC_COOLCONF_SEUP (5)
#define FB_TMC_COOLCONF_SEMIN (0)
// COOLCONF MASKS
// mask the bits from the values we want to set
const int FB_TMC_COOLCONF_MASKS[] = {
0b1111UL, // 0 FB_TMC_COOLCONF_SEMIN
0b111UL, // 1
0b11UL, // 2
0b1UL, // 3
0b0UL, // 4
0b11UL, // 5 FB_TMC_COOLCONF_SEUP
0b1UL, // 6
0b0UL, // 7
0b1111UL, // 8 FB_TMC_COOLCONF_SEMAX
0b111UL, // 9
0b11UL, // 10
0b1UL, // 11
0b0UL, // 12
0b11UL, // 13 FB_TMC_COOLCONF_SEDN
0b1UL, // 14
0b1UL, // 15 FB_TMC_COOLCONF_SEIMIN
0b1111111UL, // 16 FB_TMC_COOLCONF_SGT
0b111111UL, // 17
0b11111UL, // 18
0b1111UL, // 19
0b111UL, // 20
0b11UL, // 21
0b1UL, // 22
0b0UL, // 23
0b1UL, // 24 FB_TMC_COOLCONF_SFILT
};
// DCCTRL OFFSETS
// for shifting incoming values to the right register position
#define FB_TMC_DCCTRL_DC_TIME (0)
#define FB_TMC_DCCTRL_DC_SG (16)
// DCCTRL MASKS
// mask the bits from the values we want to set
#define FB_TMC_DCCTRL_MASK (0b1111111111UL)
#define FB_TMC_DCCTRL_DC_TIME_MASK (0b11111111UL)
#define FB_TMC_DCCTRL_DC_SG_MASK (0b111111110000001111111111UL)
// PWMCONF OFFSETS
// for shifting incoming values to the right register position
#define FB_TMC_PWMCONF_FREEWHEEL (20)
#define FB_TMC_PWMCONF_PWM_SYMMETRIC (19)
#define FB_TMC_PWMCONF_PWM_AUTOSCALE (18)
#define FB_TMC_PWMCONF_PWM_FREQ (16)
#define FB_TMC_PWMCONF_PWM_GRAD (8)
#define FB_TMC_PWMCONF_PWM_AMPL (0)
// PWMCONF MASKS
// mask the bits from the values we want to set
const int FB_TMC_PWMCONF_MASKS[] = {
0b11111111UL, // 0 FB_TMC_PWMCONF_PWM_AMPL
0b1111111UL, // 1
0b111111UL, // 2
0b11111UL, // 3
0b1111UL, // 4
0b111UL, // 5
0b11UL, // 6
0b1UL, // 7
0b11111111UL, // 8 FB_TMC_PWMCONF_PWM_GRAD
0b1111111UL, // 9
0b111111UL, // 10
0b11111UL, // 11
0b1111UL, // 12
0b111UL, // 13
0b11UL, // 14
0b1UL, // 15
0b11UL, // 16 FB_TMC_PWMCONF_PWM_FREQ
0b1UL, // 17
0b1UL, // 18 FB_TMC_PWMCONF_PWM_AUTOSCALE
0b1UL, // 19 FB_TMC_PWMCONF_PWM_SYMMETRIC
0b11UL, // 20 FB_TMC_PWMCONF_FREEWHEEL
0b1UL, // 21
};
// ENCM_CTRL MASK
// mask the bits from the values we want to set
#define FB_TMC_ENCM_CTRL_MASK (0b11);
#endif // TMC2130_BASICS_REG_H

View File

@ -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
@ -581,46 +572,6 @@ void startSerial()
Serial.print(CRLF);
}
#if defined(FARMDUINO_EXP_V20)
void startupTmc()
{
// Initialize the drivers
Serial.print(COMM_REPORT_COMMENT);
Serial.print(SPACE);
Serial.print("Init TMC2130 drivers");
Serial.print(CRLF);
TMC2130X->begin();
TMC2130Y->begin();
TMC2130Z->begin();
TMC2130E->begin();
// Load the motor parameters
Serial.print(COMM_REPORT_COMMENT);
Serial.print(SPACE);
Serial.print("Load TMC2130 parameters");
Serial.print(CRLF);
Movement::getInstance()->initTMC2130();
Movement::getInstance()->loadSettingsTMC2130();
/*
Serial.print(COMM_REPORT_COMMENT);
Serial.print(SPACE);
Serial.print("Set shaft dir");
Serial.print(CRLF);
TMC2130X->shaft_dir(0);
TMC2130Y->shaft_dir(0);
TMC2130Z->shaft_dir(0);
TMC2130E->shaft_dir(0);
*/
}
#endif
void startInterrupt()
{
Serial.print(COMM_REPORT_COMMENT);
@ -748,6 +699,13 @@ void startServo()
}
#if defined(FARMDUINO_EXP_V20)
/**/
//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()
{
Serial.print(COMM_REPORT_COMMENT);
@ -755,150 +713,53 @@ void loadTMC2130drivers()
Serial.print("Load TMC drivers");
Serial.print(CRLF);
TMC2130Stepper controllerTMC2130_X = TMC2130Stepper(X_CHIP_SELECT);
TMC2130Stepper controllerTMC2130_Y = TMC2130Stepper(Y_CHIP_SELECT);
TMC2130Stepper controllerTMC2130_Z = TMC2130Stepper(Z_CHIP_SELECT);
TMC2130Stepper controllerTMC2130_E = TMC2130Stepper(E_CHIP_SELECT);
/**/
//TMC2130X.init();
//TMC2130Y.init();
//TMC2130Z.init();
//TMC2130E.init();
TMC2130X = &controllerTMC2130_X;
TMC2130Y = &controllerTMC2130_Y;
TMC2130Z = &controllerTMC2130_Z;
TMC2130E = &controllerTMC2130_E;
//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);
int motorCurrentX;
int stallSensitivityX;
int microStepsX;
int motorCurrentY;
int stallSensitivityY;
int microStepsY;
int motorCurrentZ;
int stallSensitivityZ;
int microStepsZ;
motorCurrentX = 600;
stallSensitivityX = 0;
microStepsX = 0;
motorCurrentY = 600;
stallSensitivityY = 0;
microStepsY = 0;
motorCurrentZ = 600;
stallSensitivityZ = 0;
microStepsZ = 0;
motorCurrentX = ParameterList::getInstance()->getValue(MOVEMENT_MOTOR_CURRENT_X);
stallSensitivityX = ParameterList::getInstance()->getValue(MOVEMENT_STALL_SENSITIVITY_X);
microStepsX = ParameterList::getInstance()->getValue(MOVEMENT_MICROSTEPS_X);
motorCurrentY = ParameterList::getInstance()->getValue(MOVEMENT_MOTOR_CURRENT_Y);
stallSensitivityY = ParameterList::getInstance()->getValue(MOVEMENT_STALL_SENSITIVITY_Y);
microStepsY = ParameterList::getInstance()->getValue(MOVEMENT_MICROSTEPS_Y);
motorCurrentZ = ParameterList::getInstance()->getValue(MOVEMENT_MOTOR_CURRENT_Z);
stallSensitivityZ = ParameterList::getInstance()->getValue(MOVEMENT_STALL_SENSITIVITY_Z);
microStepsX = ParameterList::getInstance()->getValue(MOVEMENT_MICROSTEPS_Z);
/*
TMC2130X->push();
TMC2130X->toff(3);
TMC2130X->tbl(1);
TMC2130X->hysteresis_start(4);
TMC2130X->hysteresis_end(-2);
TMC2130X->rms_current(motorCurrentX); // mA
TMC2130X->microsteps(microStepsX);
TMC2130X->diag1_stall(1);
TMC2130X->diag1_active_high(1);
TMC2130X->coolstep_min_speed(0xFFFFF); // 20bit max
TMC2130X->THIGH(0);
TMC2130X->semin(5);
TMC2130X->semax(2);
TMC2130X->sedn(0b01);
TMC2130X->sg_stall_value(stallSensitivityX);
TMC2130Y->push();
TMC2130Y->toff(3);
TMC2130Y->tbl(1);
TMC2130Y->hysteresis_start(4);
TMC2130Y->hysteresis_end(-2);
TMC2130Y->rms_current(motorCurrentY); // mA
TMC2130Y->microsteps(microStepsY);
TMC2130Y->diag1_stall(1);
TMC2130Y->diag1_active_high(1);
TMC2130Y->coolstep_min_speed(0xFFFFF); // 20bit max
TMC2130Y->THIGH(0);
TMC2130Y->semin(5);
TMC2130Y->semax(2);
TMC2130Y->sedn(0b01);
TMC2130Y->sg_stall_value(stallSensitivityY);
TMC2130Z->push();
TMC2130Z->toff(3);
TMC2130Z->tbl(1);
TMC2130Z->hysteresis_start(4);
TMC2130Z->hysteresis_end(-2);
TMC2130Z->rms_current(motorCurrentZ); // mA
TMC2130Z->microsteps(microStepsZ);
TMC2130Z->diag1_stall(1);
TMC2130Z->diag1_active_high(1);
TMC2130Z->coolstep_min_speed(0xFFFFF); // 20bit max
TMC2130Z->THIGH(0);
TMC2130Z->semin(5);
TMC2130Z->semax(2);
TMC2130Z->sedn(0b01);
TMC2130Z->sg_stall_value(stallSensitivityZ);
TMC2130E->push();
TMC2130E->toff(3);
TMC2130E->tbl(1);
TMC2130E->hysteresis_start(4);
TMC2130E->hysteresis_end(-2);
TMC2130E->rms_current(motorCurrentX); // mA
TMC2130E->microsteps(microStepsX);
TMC2130E->diag1_stall(1);
TMC2130E->diag1_active_high(1);
TMC2130E->coolstep_min_speed(0xFFFFF); // 20bit max
TMC2130E->THIGH(0);
TMC2130E->semin(5);
TMC2130E->semax(2);
TMC2130E->sedn(0b01);
TMC2130E->sg_stall_value(stallSensitivityX);
*/
TMC2130X->rms_current(motorCurrentX); // Set the required current in mA
TMC2130X->microsteps(microStepsX); // Minimum of micro steps needed
TMC2130X->chm(true); // Set the chopper mode to classic const. off time
TMC2130X->diag1_stall(1); // Activate stall diagnostics
TMC2130X->sgt(stallSensitivityX); // Set stall detection sensitivity. most -64 to +64 least
TMC2130X->shaft_dir(0); // Set direction
TMC2130Y->rms_current(motorCurrentX); // Set the required current in mA
TMC2130Y->microsteps(microStepsX); // Minimum of micro steps needed
TMC2130Y->chm(true); // Set the chopper mode to classic const. off time
TMC2130Y->diag1_stall(1); // Activate stall diagnostics
TMC2130Y->sgt(stallSensitivityX); // Set stall detection sensitivity. most -64 to +64 least
TMC2130Y->shaft_dir(0); // Set direction
TMC2130Z->rms_current(motorCurrentX); // Set the required current in mA
TMC2130Z->microsteps(microStepsX); // Minimum of micro steps needed
TMC2130Z->chm(true); // Set the chopper mode to classic const. off time
TMC2130Z->diag1_stall(1); // Activate stall diagnostics
TMC2130Z->sgt(stallSensitivityX); // Set stall detection sensitivity. most -64 to +64 least
TMC2130Z->shaft_dir(0); // Set direction
TMC2130E->rms_current(motorCurrentX); // Set the required current in mA
TMC2130E->microsteps(microStepsX); // Minimum of micro steps needed
TMC2130E->chm(true); // Set the chopper mode to classic const. off time
TMC2130E->diag1_stall(1); // Activate stall diagnostics
TMC2130E->sgt(stallSensitivityX); // Set stall detection sensitivity. most -64 to +64 least
TMC2130E->shaft_dir(0); // Set direction
//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();
}
void startupTmc()
{
// Initialize the drivers
Serial.print(COMM_REPORT_COMMENT);
Serial.print(SPACE);
Serial.print("Init TMC2130 drivers");
Serial.print(CRLF);
Movement::getInstance()->initTMC2130();
//loadTMC2130parameters();
//TMC2130X.init();
//TMC2130Y.init();
//TMC2130Z.init();
//TMC2130E.init();
//Movement::getInstance()->initTMC2130();
}
#endif
@ -906,4 +767,135 @@ 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);
/*
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");
}
*/
/*
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();
//}
}

View File

@ -16,9 +16,10 @@
#include "MemoryFree.h"
#include "Debug.h"
#include "TMC2130.h"
#if defined(FARMDUINO_EXP_V20)
#include "TMC2130.h"
#endif
/**/
#include "Movement.h"
#include "ServoControl.h"
#include "PinGuard.h"
@ -61,6 +62,7 @@ void setup();
void startServo();
void startInterrupt();
void homeOnBoot();
void setupTestForDebug();
void runTestForDebug();
void checkEncoders();
void checkPinGuard();

View File

@ -4,21 +4,31 @@
Author: Tim Evers
*/
#include "TMC2130_Basics.h"
#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)
loadTMC2130drivers();
//loadTMC2130parameters();
startupTmc();
loadTMC2130parameters();
#endif
//Serial.print("============");
//Serial.print(CRLF);
loadMovementSetting();
startMotor();
startPinGuard();
@ -27,11 +37,112 @@ void setup()
initLastAction();
homeOnBoot();
//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
@ -46,4 +157,4 @@ void loop()
checkParamsChanged();
periodicChecksAndReport();
}
}

View File

@ -126,13 +126,7 @@
<ClCompile Include="StatusList.cpp" />
<ClCompile Include="TimerOne.cpp" />
<ClCompile Include="TMC2130.cpp" />
<ClCompile Include="TMC2130\TMC2130Stepper.cpp" />
<ClCompile Include="TMC2130\TMC2130Stepper_CHOPCONF.cpp" />
<ClCompile Include="TMC2130\TMC2130Stepper_COOLCONF.cpp" />
<ClCompile Include="TMC2130\TMC2130Stepper_DRV_STATUS.cpp" />
<ClCompile Include="TMC2130\TMC2130Stepper_GCONF.cpp" />
<ClCompile Include="TMC2130\TMC2130Stepper_IHOLD_IRUN.cpp" />
<ClCompile Include="TMC2130\TMC2130Stepper_PWMCONF.cpp" />
<ClCompile Include="TMC2130_Basics.cpp" />
</ItemGroup>
<ItemGroup>
<ClInclude Include="Board.h" />
@ -180,10 +174,8 @@
<ClInclude Include="StatusList.h" />
<ClInclude Include="TimerOne.h" />
<ClInclude Include="TMC2130.h" />
<ClInclude Include="TMC2130\TMC2130Stepper.h" />
<ClInclude Include="TMC2130\TMC2130Stepper_MACROS.h" />
<ClInclude Include="TMC2130\TMC2130Stepper_REGDEFS.h" />
<ClInclude Include="TMC2130\TMC2130Stepper_UTILITY.h" />
<ClInclude Include="TMC2130_Basics.h" />
<ClInclude Include="TMC2130_Basics_Reg.h" />
<ClInclude Include="__vm\.farmbot-arduino-controller.vsarduino.h" />
<ClInclude Include="__vm\.farmbot-arduino-firmware.vsarduino.h" />
<ClInclude Include="__vm\.src.vsarduino.h" />

View File

@ -138,25 +138,7 @@
<ClCompile Include="MovementEncoder.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="TMC2130\TMC2130Stepper_CHOPCONF.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="TMC2130\TMC2130Stepper_COOLCONF.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="TMC2130\TMC2130Stepper_DRV_STATUS.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="TMC2130\TMC2130Stepper_GCONF.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="TMC2130\TMC2130Stepper_IHOLD_IRUN.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="TMC2130\TMC2130Stepper_PWMCONF.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="TMC2130\TMC2130Stepper.cpp">
<ClCompile Include="TMC2130_Basics.cpp">
<Filter>Source Files</Filter>
</ClCompile>
</ItemGroup>
@ -302,16 +284,10 @@
<ClInclude Include="MovementEncoder.h">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="TMC2130\TMC2130Stepper_MACROS.h">
<ClInclude Include="TMC2130_Basics.h">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="TMC2130\TMC2130Stepper_REGDEFS.h">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="TMC2130\TMC2130Stepper_UTILITY.h">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="TMC2130\TMC2130Stepper.h">
<ClInclude Include="TMC2130_Basics_Reg.h">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="__vm\.farmbot-arduino-firmware.vsarduino.h">