integrating TMC2130

pull/118/head
Tim Evers 2019-03-13 20:57:43 +01:00
parent ad9681db43
commit 71732a7cfa
22 changed files with 1671 additions and 856 deletions

83
src/SW_SPI.cpp 100644
View File

@ -0,0 +1,83 @@
#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;
}

25
src/SW_SPI.h 100644
View File

@ -0,0 +1,25 @@
#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

@ -39,7 +39,7 @@ void StepperControl::reportStatus(StepperControlAxis *axis, int axisStatus)
{
serialBuffer += COMM_REPORT_CMD_STATUS;
serialBuffer += " ";
serialBuffer += axis->label;
serialBuffer += axis->channelLabel;
serialBuffer += axisStatus;
serialBuffer += CurrentState::getInstance()->getQAndNewLine();
@ -54,7 +54,7 @@ void StepperControl::reportCalib(StepperControlAxis *axis, int calibStatus)
{
Serial.print(COMM_REPORT_CALIB_STATUS);
Serial.print(" ");
Serial.print(axis->label);
Serial.print(axis->channelLabel);
Serial.print(calibStatus);
CurrentState::getInstance()->printQAndNewLine();
}
@ -120,13 +120,14 @@ StepperControl::StepperControl()
// Create the axis controllers
axisX = StepperControlAxis();
axisY = StepperControlAxis();
axisZ = StepperControlAxis();
/**/ // axisX = StepperControlAxisTMC2130();
axisX = StepperControlAxisA4988();
axisY = StepperControlAxisA4988();
axisZ = StepperControlAxisA4988();
axisX.label = 'X';
axisY.label = 'Y';
axisZ.label = 'Z';
axisX.channelLabel = 'X';
axisY.channelLabel = 'Y';
axisZ.channelLabel = 'Z';
// Create the encoder controller
@ -176,26 +177,28 @@ void StepperControl::loadSettings()
void StepperControl::test()
{
Serial.print("R99");
Serial.print(" mot x = ");
Serial.print(axisX.currentPosition());
Serial.print(" enc x = ");
Serial.print(encoderX.currentPosition());
Serial.print("\r\n");
axisX.setMotorStep();
Serial.print("R99");
Serial.print(" mot y = ");
Serial.print(axisY.currentPosition());
Serial.print(" enc y = ");
Serial.print(encoderY.currentPosition());
Serial.print("\r\n");
//Serial.print("R99");
//Serial.print(" mot x = ");
//Serial.print(axisX.currentPosition());
//Serial.print(" enc x = ");
//Serial.print(encoderX.currentPosition());
//Serial.print("\r\n");
Serial.print("R99");
Serial.print(" mot z = ");
Serial.print(axisZ.currentPosition());
Serial.print(" enc z = ");
Serial.print(encoderZ.currentPosition());
Serial.print("\r\n");
//Serial.print("R99");
//Serial.print(" mot y = ");
//Serial.print(axisY.currentPosition());
//Serial.print(" enc y = ");
//Serial.print(encoderY.currentPosition());
//Serial.print("\r\n");
//Serial.print("R99");
//Serial.print(" mot z = ");
//Serial.print(axisZ.currentPosition());
//Serial.print(" enc z = ");
//Serial.print(encoderZ.currentPosition());
//Serial.print("\r\n");
// read changes in encoder
//encoderX.readEncoder();
@ -877,7 +880,7 @@ int StepperControl::calibrateAxis(int axis)
Serial.print("R99");
Serial.print(" axis ");
Serial.print(calibAxis->label);
Serial.print(calibAxis->channelLabel);
Serial.print(" move to start for calibration");
Serial.print("\r\n");
@ -982,7 +985,7 @@ int StepperControl::calibrateAxis(int axis)
Serial.print("R99");
Serial.print(" axis ");
Serial.print(calibAxis->label);
Serial.print(calibAxis->channelLabel);
Serial.print(" at starting point");
Serial.print("\r\n");
@ -1019,7 +1022,7 @@ int StepperControl::calibrateAxis(int axis)
Serial.print("R99");
Serial.print(" axis ");
Serial.print(calibAxis->label);
Serial.print(calibAxis->channelLabel);
Serial.print(" calibrating length");
Serial.print("\r\n");
@ -1102,7 +1105,7 @@ int StepperControl::calibrateAxis(int axis)
Serial.print("R99");
Serial.print(" axis ");
Serial.print(calibAxis->label);
Serial.print(calibAxis->channelLabel);
Serial.print(" at end point");
Serial.print("\r\n");

View File

@ -20,7 +20,7 @@
#include "Command.h"
#include "StepperControlAxisA4988.h"
#include "StepperControlAxisTMC2130.h"
//#include "StepperControlAxisTMC2130.h"
class StepperControl
{
@ -65,6 +65,7 @@ public:
unsigned long i4 = 0;
private:
/**///StepperControlAxisTMC2130 axisX = StepperControlAxisTMC2130();
StepperControlAxis axisX;
StepperControlAxis axisY;
StepperControlAxis axisZ;

View File

@ -1,6 +1,11 @@
#include "StepperControlAxis.h"
StepperControlAxis::StepperControlAxis()
{
init();
}
void StepperControlAxis::init()
{
lastCalcLog = 0;

View File

@ -75,12 +75,14 @@ public:
void activateDebugPrint();
void test();
char label;
char channelLabel;
bool movementStarted;
private:
protected:
int lastCalcLog = 0;
bool debugPrint = false;
void init();
// pin settings primary motor
int pinStep;

View File

@ -77,7 +77,7 @@ public:
void activateDebugPrint();
void test();
char label;
char channelLabel;
bool movementStarted;
private:

View File

@ -2,41 +2,16 @@
StepperControlAxisTMC2130::StepperControlAxisTMC2130()
{
lastCalcLog = 0;
pinStep = 0;
pinDirection = 0;
pinEnable = 0;
TMC2130A.begin(); // Initiate pins and registeries
TMC2130A.SilentStepStick2130(600); // Set stepper current to 600mA
TMC2130A.stealthChop(1); // Enable extremely quiet stepping
pin2Step = 0;
pin2Direction = 0;
pin2Enable = 0;
TMC2130B.begin(); // Initiate pins and registeries
TMC2130B.SilentStepStick2130(600); // Set stepper current to 600mA
TMC2130B.stealthChop(1); // Enable extremely quiet stepping
pinMin = 0;
pinMax = 0;
axisActive = false;
coordSourcePoint = 0;
coordCurrentPoint = 0;
coordDestinationPoint = 0;
coordHomeAxis = 0;
movementUp = false;
movementToHome = false;
movementAccelerating = false;
movementDecelerating = false;
movementCruising = false;
movementCrawling = false;
movementMotorActive = false;
movementMoving = false;
stepIsOn = false;
setMotorStepWrite = &StepperControlAxisTMC2130::setMotorStepWriteDefault;
setMotorStepWrite2 = &StepperControlAxisTMC2130::setMotorStepWriteDefault2;
resetMotorStepWrite = &StepperControlAxisTMC2130::resetMotorStepWriteDefault;
resetMotorStepWrite2 = &StepperControlAxisTMC2130::resetMotorStepWriteDefault2;
init();
}
@ -45,342 +20,9 @@ void StepperControlAxisTMC2130::test()
Serial.print("R99");
Serial.print(" cur loc = ");
Serial.print(coordCurrentPoint);
//Serial.print(" enc loc = ");
//Serial.print(coordEncoderPoint);
//Serial.print(" cons steps missed = ");
//Serial.print(label);
//Serial.print(consMissedSteps);
Serial.print("\r\n");
}
unsigned int StepperControlAxisTMC2130::calculateSpeed(long sourcePosition, long currentPosition, long destinationPosition, long minSpeed, long maxSpeed, long stepsAccDec)
{
int newSpeed = 0;
long curPos = abs(currentPosition);
long staPos;
long endPos;
movementAccelerating = false;
movementDecelerating = false;
movementCruising = false;
movementCrawling = false;
movementMoving = false;
/*
if (abs(sourcePosition) < abs(destinationPosition))
{
staPos = abs(sourcePosition);
endPos = abs(destinationPosition);
}
else
{
staPos = abs(destinationPosition);
endPos = abs(sourcePosition);
}
*/
// Set the possible negative coordinates to all positive numbers
// so the calculation code still works after the changes
staPos = 0;
endPos = abs(destinationPosition - sourcePosition);
if (sourcePosition < destinationPosition)
{
curPos = currentPosition - sourcePosition;
}
else
{
curPos = currentPosition - destinationPosition;
}
unsigned long halfway = ((endPos - staPos) / 2) + staPos;
//unsigned long halfway = ((destinationPosition - sourcePosition) / 2) + sourcePosition;
// Set the homing speed if the position would be out of bounds
if (
(curPos < staPos || curPos > endPos)
// ||
// Also limit the speed to a crawl when the move would pass the home position
// (sourcePosition > 0 && destinationPosition < 0) || (sourcePosition < 0 && destinationPosition > 0)
// (!motorHomeIsUp && currentPosition <= 0) || (motorHomeIsUp && currentPosition >= 0) ||)
)
{
newSpeed = motorSpeedHome;
//newSpeed = minSpeed;
movementCrawling = true;
movementMoving = true;
}
else
{
if (curPos >= staPos && curPos <= halfway)
{
// accelerating
if (curPos > (staPos + stepsAccDec))
{
// now beyond the accelleration point to go full speed
newSpeed = maxSpeed + 1;
movementCruising = true;
movementMoving = true;
}
else
{
// speeding up, increase speed linear within the first period
newSpeed = (1.0 * (curPos - staPos) / stepsAccDec * (maxSpeed - minSpeed)) + minSpeed;
movementAccelerating = true;
movementMoving = true;
}
}
else
{
// decelerating
if (curPos < (endPos - stepsAccDec))
{
// still before the deceleration point so keep going at full speed
newSpeed = maxSpeed + 2;
movementCruising = true;
movementMoving = true;
}
else
{
// speeding up, increase speed linear within the first period
newSpeed = (1.0 * (endPos - curPos) / stepsAccDec * (maxSpeed - minSpeed)) + minSpeed;
movementDecelerating = true;
movementMoving = true;
}
}
}
if (debugPrint && (millis() - lastCalcLog > 1000))
{
lastCalcLog = millis();
Serial.print("R99");
Serial.print(" sta ");
Serial.print(staPos);
Serial.print(" cur ");
Serial.print(curPos);
Serial.print(" end ");
Serial.print(endPos);
Serial.print(" half ");
Serial.print(halfway);
Serial.print(" len ");
Serial.print(stepsAccDec);
Serial.print(" min ");
Serial.print(minSpeed);
Serial.print(" max ");
Serial.print(maxSpeed);
Serial.print(" spd ");
Serial.print(" ");
Serial.print(newSpeed);
Serial.print("\r\n");
}
// Return the calculated speed, in steps per second
return newSpeed;
}
void StepperControlAxisTMC2130::checkAxisDirection()
{
if (coordHomeAxis)
{
// When home is active, the direction is fixed
movementUp = motorHomeIsUp;
movementToHome = true;
}
else
{
// For normal movement, move in direction of destination
movementUp = (coordCurrentPoint < coordDestinationPoint);
movementToHome = (abs(coordCurrentPoint) >= abs(coordDestinationPoint));
}
if (coordCurrentPoint == 0)
{
// Go slow when theoretical end point reached but there is no end stop siganl
axisSpeed = motorSpeedMin;
}
}
void StepperControlAxisTMC2130::setDirectionAxis()
{
if (((!coordHomeAxis && coordCurrentPoint < coordDestinationPoint) || (coordHomeAxis && motorHomeIsUp)))
{
setDirectionUp();
}
else
{
setDirectionDown();
}
}
void StepperControlAxisTMC2130::checkMovement()
{
checkAxisDirection();
// Handle movement if destination is not already reached or surpassed
if (
(
(coordDestinationPoint > coordSourcePoint && coordCurrentPoint < coordDestinationPoint) ||
(coordDestinationPoint < coordSourcePoint && coordCurrentPoint > coordDestinationPoint) ||
coordHomeAxis) &&
axisActive)
{
// home or destination not reached, keep moving
// If end stop reached or the encoder doesn't move anymore, stop moving motor, otherwise set the timing for the next step
if ((coordHomeAxis && !endStopAxisReached(false)) || (!coordHomeAxis && !endStopAxisReached(!movementToHome)))
{
// Get the axis speed, in steps per second
axisSpeed = calculateSpeed(coordSourcePoint, coordCurrentPoint, coordDestinationPoint,
motorSpeedMin, motorSpeedMax, motorStepsAcc);
// // Set the moments when the step is set to true and false
// if (axisSpeed > 0)
// {
// Take the requested speed (steps / second) and divide by the interrupt speed (interrupts per seconde)
// This gives the number of interrupts (called ticks here) before the pulse needs to be set for the next step
// stepOnTick = moveTicks + (1000.0 * 1000.0 / motorInterruptSpeed / axisSpeed / 2);
// stepOffTick = moveTicks + (1000.0 * 1000.0 / motorInterruptSpeed / axisSpeed);
// }
}
else
{
axisActive = false;
}
}
else
{
// Destination or home reached. Deactivate the axis.
axisActive = false;
}
// If end stop for home is active, set the position to zero
if (endStopAxisReached(false))
{
coordCurrentPoint = 0;
}
}
void StepperControlAxisTMC2130::incrementTick()
{
if (axisActive)
{
moveTicks++;
//moveTicks+=3;
}
}
void StepperControlAxisTMC2130::checkTiming()
{
//int i;
// moveTicks++;
if (stepIsOn)
{
if (moveTicks >= stepOffTick)
{
// Negative flank for the steps
resetMotorStep();
setTicks();
//stepOnTick = moveTicks + (500000.0 / motorInterruptSpeed / axisSpeed);
}
}
else
{
if (axisActive)
{
if (moveTicks >= stepOnTick)
{
// Positive flank for the steps
setStepAxis();
//stepOffTick = moveTicks + (1000000.0 / motorInterruptSpeed / axisSpeed);
}
}
}
}
void StepperControlAxisTMC2130::setTicks()
{
// Take the requested speed (steps / second) and divide by the interrupt speed (interrupts per seconde)
// This gives the number of interrupts (called ticks here) before the pulse needs to be set for the next step
stepOnTick = moveTicks + (1000.0 * 1000.0 / motorInterruptSpeed / axisSpeed / 2);
stepOffTick = moveTicks + (1000.0 * 1000.0 / motorInterruptSpeed / axisSpeed);
}
void StepperControlAxisTMC2130::setStepAxis()
{
stepIsOn = true;
if (movementUp)
{
coordCurrentPoint++;
}
else
{
coordCurrentPoint--;
}
// set a step on the motors
setMotorStep();
}
bool StepperControlAxisTMC2130::endStopAxisReached(bool movement_forward)
{
bool min_endstop = false;
bool max_endstop = false;
bool invert = false;
if (motorEndStopInv)
{
invert = true;
}
// for the axis to check, retrieve the end stop status
if (!invert)
{
min_endstop = endStopMin();
max_endstop = endStopMax();
}
else
{
min_endstop = endStopMax();
max_endstop = endStopMin();
}
// if moving forward, only check the end stop max
// for moving backwards, check only the end stop min
if ((!movement_forward && min_endstop) || (movement_forward && max_endstop))
{
return 1;
}
return 0;
}
void StepperControlAxisTMC2130::loadPinNumbers(int step, int dir, int enable, int min, int max, int step2, int dir2, int enable2)
{
pinStep = step;
@ -418,83 +60,6 @@ void StepperControlAxisTMC2130::loadMotorSettings(
motorMaxSize = maxSize;
motorStopAtMax = stopAtMax;
if (pinStep == 54)
{
setMotorStepWrite = &StepperControlAxisTMC2130::setMotorStepWrite54;
resetMotorStepWrite = &StepperControlAxisTMC2130::resetMotorStepWrite54;
}
if (pinStep == 60)
{
setMotorStepWrite = &StepperControlAxisTMC2130::setMotorStepWrite60;
resetMotorStepWrite = &StepperControlAxisTMC2130::resetMotorStepWrite60;
}
if (pinStep == 46)
{
setMotorStepWrite = &StepperControlAxisTMC2130::setMotorStepWrite46;
resetMotorStepWrite = &StepperControlAxisTMC2130::resetMotorStepWrite46;
}
if (pin2Step == 26)
{
setMotorStepWrite2 = &StepperControlAxisTMC2130::setMotorStepWrite26;
resetMotorStepWrite2 = &StepperControlAxisTMC2130::resetMotorStepWrite26;
}
}
bool StepperControlAxisTMC2130::loadCoordinates(long sourcePoint, long destinationPoint, bool home)
{
coordSourcePoint = sourcePoint;
coordCurrentPoint = sourcePoint;
coordDestinationPoint = destinationPoint;
coordHomeAxis = home;
bool changed = false;
// Limit normal movement to the home position
if (motorStopAtHome)
{
if (!motorHomeIsUp && coordDestinationPoint < 0)
{
coordDestinationPoint = 0;
changed = true;
}
if (motorHomeIsUp && coordDestinationPoint > 0)
{
coordDestinationPoint = 0;
changed = true;
}
}
// limit the maximum size the bot can move, when there is a size present
if (motorMaxSize > 0 && motorStopAtMax)
{
if (abs(coordDestinationPoint) > abs(motorMaxSize))
{
if (coordDestinationPoint < 0)
{
coordDestinationPoint = -abs(motorMaxSize);
changed = true;
}
else
{
coordDestinationPoint = abs(motorMaxSize);
changed = true;
}
}
}
// Initialize movement variables
moveTicks = 0;
axisActive = true;
return changed;
}
void StepperControlAxisTMC2130::enableMotor()
@ -522,20 +87,20 @@ void StepperControlAxisTMC2130::setDirectionUp()
if (motorMotorInv)
{
digitalWrite(pinDirection, LOW);
TMC2130A.shaft_dir(0);
}
else
{
digitalWrite(pinDirection, HIGH);
TMC2130A.shaft_dir(1);
}
if (motorMotor2Enl && motorMotor2Inv)
{
digitalWrite(pin2Direction, LOW);
TMC2130B.shaft_dir(0);
}
else
{
digitalWrite(pin2Direction, HIGH);
TMC2130B.shaft_dir(1);
}
}
@ -543,275 +108,54 @@ void StepperControlAxisTMC2130::setDirectionDown()
{
if (motorMotorInv)
{
digitalWrite(pinDirection, HIGH);
TMC2130A.shaft_dir(1);
}
else
{
digitalWrite(pinDirection, LOW);
TMC2130A.shaft_dir(0);
}
if (motorMotor2Enl && motorMotor2Inv)
{
digitalWrite(pin2Direction, HIGH);
TMC2130B.shaft_dir(1);
}
else
{
digitalWrite(pin2Direction, LOW);
TMC2130B.shaft_dir(0);
}
}
void StepperControlAxisTMC2130::setMovementUp()
{
movementUp = true;
}
void StepperControlAxisTMC2130::setMovementDown()
{
movementUp = false;
}
void StepperControlAxisTMC2130::setDirectionHome()
{
if (motorHomeIsUp)
{
setDirectionUp();
setMovementUp();
}
else
{
setDirectionDown();
setMovementDown();
}
}
void StepperControlAxisTMC2130::setDirectionAway()
{
if (motorHomeIsUp)
{
setDirectionDown();
setMovementDown();
}
else
{
setDirectionUp();
setMovementUp();
}
}
unsigned long StepperControlAxisTMC2130::getLength(long l1, long l2)
{
if (l1 > l2)
{
return l1 - l2;
}
else
{
return l2 - l1;
}
}
bool StepperControlAxisTMC2130::endStopsReached()
{
return ((digitalRead(pinMin) == motorEndStopInv2) || (digitalRead(pinMax) == motorEndStopInv2)) && motorEndStopEnbl;
}
bool StepperControlAxisTMC2130::endStopMin()
{
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
return ((digitalRead(pinMin) == motorEndStopInv2) && motorEndStopEnbl);
}
bool StepperControlAxisTMC2130::endStopMax()
{
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
return ((digitalRead(pinMax) == motorEndStopInv2) && motorEndStopEnbl);
}
bool StepperControlAxisTMC2130::isAxisActive()
{
return axisActive;
}
void StepperControlAxisTMC2130::deactivateAxis()
{
axisActive = false;
}
void StepperControlAxisTMC2130::setMotorStep()
{
stepIsOn = true;
//digitalWrite(pinStep, HIGH);
(this->*setMotorStepWrite)();
if (pin2Enable)
// TMC2130 works on each edge, so instead of setting the
// step bit, toggle the bit here
if (!tmcStep)
{
(this->*setMotorStepWrite2)();
//digitalWrite(pin2Step, HIGH);
/**/Serial.print("R99 HIGH \r\n");
digitalWrite(pinStep, HIGH);
if (pin2Enable)
{
digitalWrite(pin2Step, HIGH);
}
}
else
{
/**/Serial.print("R99 LOW \r\n");
digitalWrite(pinStep, LOW);
if (pin2Enable)
{
digitalWrite(pin2Step, LOW);
}
}
tmcStep = !tmcStep;
}
void StepperControlAxisTMC2130::resetMotorStep()
{
// No reset needed for TMC2130
stepIsOn = false;
movementStepDone = true;
digitalWrite(pinStep, LOW);
//(this->*resetMotorStepWrite)();
if (pin2Enable)
{
digitalWrite(pin2Step, LOW);
//(this->*resetMotorStepWrite2)();
}
}
bool StepperControlAxisTMC2130::pointReached(long currentPoint, long destinationPoint)
{
return (destinationPoint == currentPoint);
}
long StepperControlAxisTMC2130::currentPosition()
{
return coordCurrentPoint;
}
void StepperControlAxisTMC2130::setCurrentPosition(long newPos)
{
coordCurrentPoint = newPos;
}
long StepperControlAxisTMC2130::destinationPosition()
{
return coordDestinationPoint;
}
void StepperControlAxisTMC2130::setMaxSpeed(long speed)
{
motorSpeedMax = speed;
}
void StepperControlAxisTMC2130::activateDebugPrint()
{
debugPrint = true;
}
bool StepperControlAxisTMC2130::isStepDone()
{
return movementStepDone;
}
void StepperControlAxisTMC2130::resetStepDone()
{
movementStepDone = false;
}
bool StepperControlAxisTMC2130::movingToHome()
{
return movementToHome;
}
bool StepperControlAxisTMC2130::movingUp()
{
return movementUp;
}
bool StepperControlAxisTMC2130::isAccelerating()
{
return movementAccelerating;
}
bool StepperControlAxisTMC2130::isDecelerating()
{
return movementDecelerating;
}
bool StepperControlAxisTMC2130::isCruising()
{
return movementCruising;
}
bool StepperControlAxisTMC2130::isCrawling()
{
return movementCrawling;
}
bool StepperControlAxisTMC2130::isMotorActive()
{
return movementMotorActive;
}
/// Functions for pin writing using alternative method
// Pin write default functions
void StepperControlAxisTMC2130::setMotorStepWriteDefault()
{
digitalWrite(pinStep, HIGH);
}
void StepperControlAxisTMC2130::setMotorStepWriteDefault2()
{
digitalWrite(pin2Step, HIGH);
}
void StepperControlAxisTMC2130::resetMotorStepWriteDefault()
{
digitalWrite(pinStep, LOW);
}
void StepperControlAxisTMC2130::resetMotorStepWriteDefault2()
{
digitalWrite(pin2Step, LOW);
}
// X step
void StepperControlAxisTMC2130::setMotorStepWrite54()
{
//PF0
PORTF |= B00000001;
}
void StepperControlAxisTMC2130::resetMotorStepWrite54()
{
//PF0
PORTF &= B11111110;
}
// X step 2
void StepperControlAxisTMC2130::setMotorStepWrite26()
{
//PA4
PORTA |= B00010000;
}
void StepperControlAxisTMC2130::resetMotorStepWrite26()
{
PORTA &= B11101111;
}
// Y step
void StepperControlAxisTMC2130::setMotorStepWrite60()
{
//PF6
PORTF |= B01000000;
}
void StepperControlAxisTMC2130::resetMotorStepWrite60()
{
//PF6
PORTF &= B10111111;
}
// Z step
void StepperControlAxisTMC2130::setMotorStepWrite46()
{
//PL3
PORTL |= B00001000;
}
void StepperControlAxisTMC2130::resetMotorStepWrite46()
{
//PL3
PORTL &= B11110111;
}
}

View File

@ -19,6 +19,8 @@
#include "StepperControlAxis.h"
#include "TMC2130Stepper.h"
class StepperControlAxisTMC2130 : public StepperControlAxis
{
@ -27,146 +29,27 @@ public:
void loadPinNumbers(int step, int dir, int enable, int min, int max, int step2, int dir2, int enable2);
void loadMotorSettings(long speedMax, long speedMin, long speedHome, long stepsAcc, long timeOut, bool homeIsUp, bool motorInv, bool endStInv, bool endStInv2, long interruptSpeed, bool motor2Enbl, bool motor2Inv, bool endStEnbl, bool stopAtHome, long maxSize, bool stopAtMax);
bool loadCoordinates(long sourcePoint, long destinationPoint, bool home);
void setMaxSpeed(long speed);
void enableMotor();
void disableMotor();
void checkMovement();
void incrementTick();
void checkTiming();
void setTicks();
bool isAxisActive();
void deactivateAxis();
bool isAccelerating();
bool isDecelerating();
bool isCruising();
bool isCrawling();
bool isMotorActive();
bool isMoving();
bool endStopMin();
bool endStopMax();
bool endStopsReached();
bool endStopAxisReached(bool movement_forward);
long currentPosition();
void setCurrentPosition(long newPos);
long destinationPosition();
void setStepAxis();
void setMotorStep();
void resetMotorStep();
void setDirectionUp();
void setDirectionDown();
void setDirectionHome();
void setDirectionAway();
void setDirectionAxis();
void setMovementUp();
void setMovementDown();
bool movingToHome();
bool movingUp();
bool isStepDone();
void resetStepDone();
void activateDebugPrint();
void test();
char label;
char channelLabel;
bool movementStarted;
private:
int lastCalcLog = 0;
bool debugPrint = false;
// pin settings primary motor
int pinStep;
int pinDirection;
int pinEnable;
TMC2130Stepper TMC2130A = TMC2130Stepper(X_ENABLE_PIN, X_DIR_PIN, X_STEP_PIN, X_CHIP_SELECT);
TMC2130Stepper TMC2130B = TMC2130Stepper(E_ENABLE_PIN, E_DIR_PIN, E_STEP_PIN, E_CHIP_SELECT);
// pin settings primary motor
int pin2Step;
int pin2Direction;
int pin2Enable;
// pin settings primary motor
int pinMin;
int pinMax;
// motor settings
bool motorEndStopInv; // switch places of end stops
bool motorEndStopInv2; // invert input (true/normal open, falce/normal closed) of end stops
bool motorEndStopEnbl; // enable the use of the end stops
// motor settings
long motorSpeedMax; // maximum speed in steps per second
long motorSpeedMin; // minimum speed in steps per second
long motorSpeedHome; // homing speed in steps per second
long motorStepsAcc; // number of steps used for acceleration
long motorTimeOut; // timeout in seconds
bool motorHomeIsUp; // direction to move when reached 0 on axis but no end stop detected while homing
bool motorMotorInv; // invert motor direction
bool motorMotor2Enl; // enable secondary motor
bool motorMotor2Inv; // invert secondary motor direction
long motorInterruptSpeed; // period of interrupt in micro seconds
bool motorStopAtHome; // stop at home position or also use other side of the axis
long motorMaxSize; // maximum size of the axis in steps
bool motorStopAtMax; // stop at the maximum size
// coordinates
long coordSourcePoint; // all coordinated in steps
long coordCurrentPoint;
long coordDestinationPoint;
bool coordHomeAxis; // homing command
// movement handling
unsigned long movementLength;
unsigned long maxLenth;
unsigned long moveTicks;
unsigned long stepOnTick;
unsigned long stepOffTick;
unsigned long axisSpeed;
bool axisActive;
bool movementUp;
bool movementToHome;
bool movementStepDone;
bool movementAccelerating;
bool movementDecelerating;
bool movementCruising;
bool movementCrawling;
bool movementMotorActive;
bool movementMoving;
bool stepIsOn;
void step(long &currentPoint, unsigned long steps, long destinationPoint);
bool pointReached(long currentPoint, long destinationPoint);
unsigned int calculateSpeed(long sourcePosition, long currentPosition, long destinationPosition, long minSpeed, long maxSpeed, long stepsAccDec);
unsigned long getLength(long l1, long l2);
void checkAxisDirection();
void (StepperControlAxisTMC2130::*setMotorStepWrite)();
void (StepperControlAxisTMC2130::*setMotorStepWrite2)();
void (StepperControlAxisTMC2130::*resetMotorStepWrite)();
void (StepperControlAxisTMC2130::*resetMotorStepWrite2)();
void setMotorStepWriteDefault();
void setMotorStepWriteDefault2();
void resetMotorStepWriteDefault();
void resetMotorStepWriteDefault2();
void setMotorStepWrite54();
void resetMotorStepWrite54();
void setMotorStepWrite26();
void resetMotorStepWrite26();
void setMotorStepWrite60();
void resetMotorStepWrite60();
void setMotorStepWrite46();
void resetMotorStepWrite46();
bool tmcStep = false;
};

View File

@ -0,0 +1,428 @@
#include "TMC2130Stepper.h"
#include "TMC2130Stepper_MACROS.h"
#include <SPI.h>
#include "SW_SPI.h"
TMC2130Stepper::TMC2130Stepper(uint16_t pinCS) : _pinCS(pinCS), uses_sw_spi(false) {}
TMC2130Stepper::TMC2130Stepper(uint16_t pinEN, uint16_t pinDIR, uint16_t pinStep, uint16_t pinCS) :
_pinEN(pinEN),
_pinSTEP(pinStep),
_pinCS(pinCS),
_pinDIR(pinDIR),
uses_sw_spi(false)
{}
TMC2130Stepper::TMC2130Stepper(uint16_t pinEN, uint16_t pinDIR, uint16_t pinStep, uint16_t pinCS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK) :
_pinEN(pinEN),
_pinSTEP(pinStep),
_pinCS(pinCS),
_pinDIR(pinDIR),
uses_sw_spi(true)
{ TMC_SW_SPI.setPins(pinMOSI, pinMISO, pinSCK); }
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);
if (uses_sw_spi) TMC_SW_SPI.init();
// Reset registers
push();
toff(8); //off_time(8);
tbl(1); //blank_time(24);
}
void TMC2130Stepper::send2130(uint8_t addressByte, uint32_t *config) {
if (uses_sw_spi) {
digitalWrite(_pinCS, LOW);
status_response = TMC_SW_SPI.transfer(addressByte & 0xFF); // s =
if (addressByte >> 7) { // Check if WRITE command
//*config &= ~mask; // Clear bits being set
//*config |= (value & mask); // Set new values
TMC_SW_SPI.transfer((*config >> 24) & 0xFF);
TMC_SW_SPI.transfer((*config >> 16) & 0xFF);
TMC_SW_SPI.transfer((*config >> 8) & 0xFF);
TMC_SW_SPI.transfer(*config & 0xFF);
} else { // READ command
TMC_SW_SPI.transfer16(0x0000); // Clear SPI
TMC_SW_SPI.transfer16(0x0000);
digitalWrite(_pinCS, HIGH);
digitalWrite(_pinCS, LOW);
TMC_SW_SPI.transfer(addressByte & 0xFF); // Send the address byte again
*config = TMC_SW_SPI.transfer(0x00);
*config <<= 8;
*config|= TMC_SW_SPI.transfer(0x00);
*config <<= 8;
*config|= TMC_SW_SPI.transfer(0x00);
*config <<= 8;
*config|= TMC_SW_SPI.transfer(0x00);
}
digitalWrite(_pinCS, HIGH);
} else {
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

@ -0,0 +1,446 @@
#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 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

@ -0,0 +1,68 @@
#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

@ -0,0 +1,31 @@
#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

@ -0,0 +1,29 @@
#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

@ -0,0 +1,54 @@
#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

@ -0,0 +1,16 @@
#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

@ -0,0 +1,22 @@
#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

@ -0,0 +1,24 @@
#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

@ -0,0 +1,288 @@
#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

@ -0,0 +1,33 @@
#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

@ -11,6 +11,14 @@
#include "CurrentState.h"
#include <SPI.h>
#include <TMC2130Stepper.h>
/**/ TMC2130Stepper stepper = TMC2130Stepper(X_ENABLE_PIN, X_DIR_PIN, X_STEP_PIN, X_CHIP_SELECT);
bool stepperInit = false;
bool stepperFlip = false;
static char commandEndChar = 0x0A;
static GCodeProcessor *gCodeProcessor = new GCodeProcessor();
@ -277,9 +285,11 @@ void setup()
// Interrupt management code library written by Paul Stoffregen
// The default time 100 micro seconds
Timer1.attachInterrupt(interrupt);
Timer1.initialize(MOVEMENT_INTERRUPT_SPEED);
Timer1.start();
#if !defined(FARMDUINO_EXP_V20)
Timer1.attachInterrupt(interrupt);
Timer1.initialize(MOVEMENT_INTERRUPT_SPEED);
Timer1.start();
#endif
// Initialize the inactivity check
lastAction = millis();
@ -318,8 +328,16 @@ void setup()
}
Serial.print("R99 ARDUINO STARTUP COMPLETE\r\n");
stepper.begin();
stepper.SilentStepStick2130(600);
stepper.stealthChop(1);
stepper.shaft_dir(0);
digitalWrite(X_ENABLE_PIN, LOW);
}
//char commandIn[100];
char commandChar[INCOMING_CMD_BUF_SIZE + 1];
@ -327,6 +345,15 @@ char commandChar[INCOMING_CMD_BUF_SIZE + 1];
void loop()
{
/**/
digitalWrite(X_STEP_PIN, stepperFlip);
delayMicroseconds(10);
stepperFlip != stepperFlip;
/*********************************/
if (debugInterrupt)
{
StepperControl::getInstance()->handleMovementInterrupt();
@ -355,7 +382,6 @@ void loop()
if (Serial.available())
{
// Save current time stamp for timeout actions
lastAction = millis();
@ -424,6 +450,10 @@ void loop()
incomingCommandPointer = 0;
}
}
else
{
/**/StepperControl::getInstance()->test();
}
// In case of emergency stop, disable movement and
// shut down the pins used

View File

@ -47,7 +47,7 @@
<WarningLevel>Level3</WarningLevel>
<Optimization>Disabled</Optimization>
<SDLCheck>true</SDLCheck>
<AdditionalIncludeDirectories>$(ProjectDir)..\src;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\hardware\avr\1.6.19\libraries\SPI\src;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\hardware\avr\1.6.19\libraries\EEPROM\src;$(ProjectDir)..\..\..\..\Program Files (x86)\Arduino\libraries\Servo\src;$(ProjectDir)..\..\..\..\Program Files (x86)\Arduino\libraries;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\hardware\avr\1.6.19\libraries;$(ProjectDir)..\..\..\..\Users\Bro\Documents\Arduino\libraries;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\hardware\avr\1.6.19\cores\arduino;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\hardware\avr\1.6.19\variants\mega;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\tools\avr-gcc\4.9.2-atmel3.5.4-arduino2\avr\include\;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\tools\avr-gcc\4.9.2-atmel3.5.4-arduino2\avr\include\avr\;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\tools\avr-gcc\4.9.2-atmel3.5.4-arduino2\lib\gcc\avr\4.8.1\include;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\tools\avr-gcc\4.9.2-atmel3.5.4-arduino2\lib\gcc\avr\4.9.2\include;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\tools\avr-gcc\4.9.2-atmel3.5.4-arduino2\lib\gcc\avr\4.9.3\include;%(AdditionalIncludeDirectories)</AdditionalIncludeDirectories>
<AdditionalIncludeDirectories>$(ProjectDir)..\src;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\hardware\avr\1.6.19\libraries\SPI\src;$(ProjectDir)..\..\..\..\Users\Bro\Documents\Arduino\libraries\TMC2130Stepper\src;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\hardware\avr\1.6.19\libraries\EEPROM\src;$(ProjectDir)..\..\..\..\Program Files (x86)\Arduino\libraries\Servo\src;$(ProjectDir)..\..\..\..\Program Files (x86)\Arduino\libraries;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\hardware\avr\1.6.19\libraries;$(ProjectDir)..\..\..\..\Users\Bro\Documents\Arduino\libraries;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\hardware\avr\1.6.19\cores\arduino;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\hardware\avr\1.6.19\variants\mega;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\tools\avr-gcc\4.9.2-atmel3.5.4-arduino2\avr\include\;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\tools\avr-gcc\4.9.2-atmel3.5.4-arduino2\avr\include\avr\;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\tools\avr-gcc\4.9.2-atmel3.5.4-arduino2\lib\gcc\avr\4.8.1\include;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\tools\avr-gcc\4.9.2-atmel3.5.4-arduino2\lib\gcc\avr\4.9.2\include;$(ProjectDir)..\..\..\..\Users\Bro\AppData\Local\arduino15\packages\arduino\tools\avr-gcc\4.9.2-atmel3.5.4-arduino2\lib\gcc\avr\4.9.3\include;%(AdditionalIncludeDirectories)</AdditionalIncludeDirectories>
<ForcedIncludeFiles>$(ProjectDir)__vm\.src.vsarduino.h;%(ForcedIncludeFiles)</ForcedIncludeFiles>
<IgnoreStandardIncludePath>false</IgnoreStandardIncludePath>
<PreprocessorDefinitions>__AVR_ATmega2560__;_VMDEBUG=1;F_CPU=16000000L;ARDUINO=10802;ARDUINO_AVR_MEGA2560;ARDUINO_ARCH_AVR;__cplusplus=201103L;_VMICRO_INTELLISENSE;%(PreprocessorDefinitions)</PreprocessorDefinitions>
@ -182,7 +182,7 @@
</ImportGroup>
<ProjectExtensions>
<VisualStudio>
<UserProperties vm.programmer_name="avrisp" arduino.upload.port="COM6" />
<UserProperties vm.programmer_name="avrisp" arduino.upload.port="COM3" />
</VisualStudio>
</ProjectExtensions>
</Project>