Switching to a different TMC2130 library

pull/123/head
Tim Evers 2020-01-02 22:33:34 +01:00
parent 5883ab8a78
commit 09695d338a
13 changed files with 1468 additions and 509 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,7 +234,6 @@ 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);
@ -246,6 +245,8 @@ void Movement::loadSettings()
microStepsX = ParameterList::getInstance()->getValue(MOVEMENT_MICROSTEPS_Z);
//axisZ.loadSettingsTMC2130(motorCurrent, stallSensitivity, microSteps);
/**/
motorCurrentX = 600;
stallSensitivityX = 0;
microStepsX = 0;
@ -258,70 +259,9 @@ void Movement::loadSettings()
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);
axisX.loadSettingsTMC2130(motorCurrentX, stallSensitivityX, microStepsX);
axisY.loadSettingsTMC2130(motorCurrentX, stallSensitivityX, microStepsX);
axisZ.loadSettingsTMC2130(motorCurrentX, stallSensitivityX, microStepsX);
}
#endif

View File

@ -84,7 +84,7 @@ void MovementAxis::test()
unsigned int MovementAxis::getLostSteps()
{
return TMC2130A->LOST_STEPS();
return TMC2130A->get_MSCNT();
}
void MovementAxis::initTMC2130()
@ -104,127 +104,32 @@ void MovementAxis::initTMC2130()
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
}
setMotorStepWrite = &MovementAxis::setMotorStepWriteTMC2130;
setMotorStepWrite2 = &MovementAxis::setMotorStepWriteTMC2130_2;
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, stallSensitivity, microSteps);
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, stallSensitivity, microSteps);
}
}
bool MovementAxis::stallDetected() {
return TMC2130A->stallguard();
return (TMC2130A->isStandstill() || TMC2130A->isStallguard());
}
uint16_t MovementAxis::getLoad() {

View File

@ -29,8 +29,8 @@ public:
MovementAxis();
#if defined(FARMDUINO_EXP_V20)
TMC2130Stepper *TMC2130A;
TMC2130Stepper *TMC2130B;
Trinamic_TMC2130 *TMC2130A;
Trinamic_TMC2130 *TMC2130B;
#endif
void loadPinNumbers(int step, int dir, int enable, int min, int max, int step2, int dir2, int enable2);

View File

@ -7,68 +7,36 @@
#include "TMC2130.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 TMC2130Holder *instance;
TMC2130Holder *TMC2130Holder::getInstance()
void loadTMC2130ParametersMotor(Trinamic_TMC2130 *myStepper, int microsteps, int current, int sensitivity)
{
if (!instance)
// stepper
//myStepper->init();
myStepper->set_mres(microsteps); // ({1,2,4,8,16,32,64,128,256}) number of microsteps
//myStepper->set_IHOLD_IRUN(31, 31, 5); // ([0-31],[0-31],[0-5]) sets all currents to maximum
myStepper->set_I_scale_analog(1); // ({0,1}) 0: I_REF internal, 1: sets I_REF to AIN
{
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;
}
myStepper->set_IHOLD_IRUN(CS, CS, 16);
}
TMC2130Holder::TMC2130Holder()
{
}
myStepper->set_toff(3); // ([0-15]) 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
myStepper->set_tbl(1); // ([0-3]) set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
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);
myStepper->set_diag1_stall(1);
myStepper->set_diag1_onstate(1);
myStepper->set_TCOOLTHRS(0xFFFFF);
myStepper->set_THIGH(0);
myStepper->set_semin(5);
myStepper->set_semax(2);
myStepper->set_sedn(0b01);
myStepper->set_sgt(sensitivity);
tmcTMC2130X = &TMC2130X;
tmcTMC2130Y = &TMC2130Y;
tmcTMC2130Z = &TMC2130Z;
tmcTMC2130E = &TMC2130E;
}
TMC2130Stepper* TMC2130Holder::TMC2130X()
{
return tmcTMC2130X;
}
TMC2130Stepper* TMC2130Holder::TMC2130Y()
{
return tmcTMC2130Y;
}
TMC2130Stepper* TMC2130Holder::TMC2130Z()
{
return tmcTMC2130Z;
}
c
TMC2130Stepper* TMC2130Holder::TMC2130E()
{
return tmcTMC213EZ;
}
*/
}

View File

@ -9,70 +9,25 @@
#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 "Trinamic\Trinamic_TMC2130.h"
#include "pins.h"
static TMC2130Stepper *TMC2130X;
static TMC2130Stepper *TMC2130Y;
static TMC2130Stepper *TMC2130Z;
static TMC2130Stepper *TMC2130E;
static Trinamic_TMC2130 *TMC2130X;
static Trinamic_TMC2130 *TMC2130Y;
static Trinamic_TMC2130 *TMC2130Z;
static Trinamic_TMC2130 *TMC2130E;
//Trinamic_TMC2130 TMC2130X(X_CHIP_SELECT);
//Trinamic_TMC2130 TMC2130Y(Y_CHIP_SELECT);
//Trinamic_TMC2130 TMC2130Z(Z_CHIP_SELECT);
//Trinamic_TMC2130 TMC2130E(E_CHIP_SELECT);
//static 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);
void loadTMC2130ParametersMotor(Trinamic_TMC2130 *myStepper, int microsteps, int current, int sensitivity);
//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);
//static TMC2130Stepper *TMC2130X;
//static TMC2130Stepper *TMC2130Y;
//static TMC2130Stepper *TMC2130Z;
//static TMC2130Stepper *TMC2130E;
#endif /* TMC2130_H_ */
/*
#if defined(FARMDUINO_EXP_V20)
#include <TMC2130Stepper.h>
//#include "TMC2130Stepper.h"
#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

@ -0,0 +1,912 @@
/**************************************************************************/
/*!
@file Trinamic_TMC2130.cpp
@author Moritz Walter
@license GPLv3 (see license.txt)
SPI configuration tool for Trinamic TMC2130 Motor Drivers
@section HISTORY
v0.1 - it works
*/
/**************************************************************************/
#if ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#include <SPI.h>
#include "Trinamic_TMC2130.h"
#include "Trinamic_TMC2130_registers.h"
Trinamic_TMC2130::Trinamic_TMC2130(uint8_t csPin)
{
_csPin=csPin;
_status=0;
_debug="";
}
// initialize the driver with its CS/SS pin
void Trinamic_TMC2130::init() {
pinMode(_csPin, OUTPUT);
digitalWrite(_csPin, HIGH);
init_SPI();
read_STAT();
}
// initialize SPI
void Trinamic_TMC2130::init_SPI() {
SPI.setDataMode(TMC_SPI_DATA_MODE);
SPI.setBitOrder(TMC_SPI_BIT_ORDER);
SPI.setClockDivider(TMC_SPI_CLOCK_DIVIDER);
SPI.begin();
}
// read status
uint8_t Trinamic_TMC2130::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 Trinamic_TMC2130::read_REG(uint8_t address, uint32_t *data)
{
init_SPI();
digitalWrite(_csPin, LOW);
// read address
_status = SPI.transfer(address&~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&~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 Trinamic_TMC2130::write_REG(uint8_t address, uint32_t data)
{
digitalWrite(_csPin, LOW);
// write address
_status = SPI.transfer(address|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 Trinamic_TMC2130::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 Trinamic_TMC2130::set_GCONF(uint8_t position, uint8_t value)
{
alter_REG(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 Trinamic_TMC2130::set_CHOPCONF(uint8_t position, uint8_t value)
{
alter_REG(TMC_REG_CHOPCONF, uint32_t(value)<<position, TMC_CHOPCONF_MASKS[position]<<position);
return _status;
}
//////////
// GCONF
//////////
uint8_t Trinamic_TMC2130::set_I_scale_analog(uint8_t value)
{
set_GCONF(TMC_GCONF_I_SCALE_ANALOG, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_internal_Rsense(uint8_t value)
{
set_GCONF(TMC_GCONF_INTERNAL_RSENSE, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_en_pwm_mode(uint8_t value)
{
set_GCONF(TMC_GCONF_EN_PWM_MODE, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_enc_commutation(uint8_t value)
{
set_GCONF(TMC_GCONF_ENC_COMMUTATION, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_shaft(uint8_t value)
{
set_GCONF(TMC_GCONF_SHAFT, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_diag0_error(uint8_t value)
{
set_GCONF(TMC_GCONF_DIAG0_ERROR, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_diag0_otpw(uint8_t value)
{
set_GCONF(TMC_GCONF_DIAG0_OTPW, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_diag0_stall(uint8_t value)
{
set_GCONF(TMC_GCONF_DIAG0_STALL, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_diag1_stall(uint8_t value)
{
set_GCONF(TMC_GCONF_DIAG1_STALL, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_diag1_index(uint8_t value)
{
set_GCONF(TMC_GCONF_DIAG1_INDEX, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_diag1_onstate(uint8_t value)
{
set_GCONF(TMC_GCONF_DIAG1_ONSTATE, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_diag1_steps_skipped(uint8_t value)
{
set_GCONF(TMC_GCONF_DIAG1_STEPS_SKIPPED, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_diag0_int_pushpull(uint8_t value)
{
set_GCONF(TMC_GCONF_DIAG0_INT_PUSHPULL, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_diag1_int_pushpull(uint8_t value)
{
set_GCONF(TMC_GCONF_DIAG1_INT_PUSHPULL, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_small_hysteresis(uint8_t value)
{
set_GCONF(TMC_GCONF_SMALL_HYSTERESIS, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_stop_enable(uint8_t value)
{
set_GCONF(TMC_GCONF_STOP_ENABLE, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_direct_mode(uint8_t value)
{
set_GCONF(TMC_GCONF_DIRECT_MODE, value);
return _status;
}
/*
uint8_t Trinamic_TMC2130::set_test_mode(uint8_t value)
{
set_GCONF(TMC_GCONF_TEST_MODE, value);
return _status;
}
*/
//////////
// IHOLD_IRUN
//////////
uint8_t Trinamic_TMC2130::set_IHOLD_IRUN(uint8_t ihold, uint8_t irun, uint8_t iholddelay)
{
uint32_t data;
// adding ihold
data = (( uint32_t(ihold)&TMC_IHOLD_MASK )<<TMC_IHOLD );
// adding irun
data |= (( uint32_t(irun)&TMC_IRUN_MASK )<<TMC_IRUN );
// adding iholddelay
data |= (( uint32_t(iholddelay)&TMC_IHOLDDELAY_MASK )<<TMC_IHOLDDELAY );
// writing data
write_REG(TMC_REG_IHOLD_IRUN, data);
return _status;
}
//////////
// TPOWERDOWN
//////////
uint8_t Trinamic_TMC2130::set_TPOWERDOWN(uint8_t value)
{
uint32_t data;
data = value & TMC_TPOWERDOWN_MASK;
write_REG(TMC_REG_TPOWERDOWN, data);
return _status;
}
//////////
// TSTEP
//////////
uint32_t Trinamic_TMC2130::get_TSTEP()
{
uint32_t data;
read_REG(TMC_REG_TPOWERDOWN, &data);
data &= TMC_TSTEP_MASK;
return data;
}
//////////
// TPWMTHRS
//////////
uint8_t Trinamic_TMC2130::set_TPWMTHRS(uint32_t value)
{
uint32_t data;
data = value & TMC_TPWMTHRS_MASK;
write_REG(TMC_REG_TPOWERDOWN, data);
return _status;
}
//////////
// TCOOLTHRS
//////////
uint8_t Trinamic_TMC2130::set_TCOOLTHRS(uint32_t value)
{
uint32_t data;
data = value & TMC_TCOOLTHRS_MASK;
write_REG(TMC_REG_TCOOLTHRS, data);
return _status;
}
//////////
// THIGH
//////////
uint8_t Trinamic_TMC2130::set_THIGH(uint32_t value)
{
uint32_t data;
data = value & TMC_THIGH_MASK;
write_REG(TMC_REG_THIGH, data);
return _status;
}
//////////
// XDIRECT
//////////
uint8_t Trinamic_TMC2130::set_XDIRECT(int16_t coil_a, int16_t coil_b)
{
uint32_t data;
data = 0x0;
data |= ( coil_b & TMC_XDIRECT_COIL_B_MASK );
data = data << TMC_XDIRECT_COIL_B;
data |= ( coil_a & TMC_XDIRECT_COIL_A_MASK );
data &= TMC_XDIRECT_MASK;
write_REG(TMC_REG_XDIRECT, data);
return _status;
}
uint8_t Trinamic_TMC2130::set_XDIRECT(uint32_t value)
{
uint32_t data;
data = value;// & TMC_XDIRECT_MASK;
write_REG(TMC_REG_XDIRECT, data);
return _status;
}
int32_t Trinamic_TMC2130::get_XDIRECT()
{
uint32_t data;
read_REG(TMC_REG_XDIRECT, &data);
data &= TMC_XDIRECT_MASK;
return data;
}
//////////
// VDCMIN
//////////
uint8_t Trinamic_TMC2130::set_VDCMIN(int32_t value)
{
int32_t data;
data = value & TMC_VDCMIN_MASK;
write_REG(TMC_REG_VDCMIN, data);
return _status;
}
//////////
// MSLUT
//////////
uint8_t Trinamic_TMC2130::set_MSLUT0(uint32_t value)
{
write_REG(TMC_REG_MSLUT0, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_MSLUT1(uint32_t value)
{
write_REG(TMC_REG_MSLUT1, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_MSLUT2(uint32_t value)
{
write_REG(TMC_REG_MSLUT2, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_MSLUT3(uint32_t value)
{
write_REG(TMC_REG_MSLUT3, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_MSLUT4(uint32_t value)
{
write_REG(TMC_REG_MSLUT4, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_MSLUT5(uint32_t value)
{
write_REG(TMC_REG_MSLUT5, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_MSLUT6(uint32_t value)
{
write_REG(TMC_REG_MSLUT6, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_MSLUT7(uint32_t value)
{
write_REG(TMC_REG_MSLUT7, value);
return _status;
}
//////////
// MSLUTSEL
//////////
uint8_t Trinamic_TMC2130::set_MSLUTSEL(uint32_t value)
{
write_REG(TMC_REG_MSLUTSEL, value);
return _status;
}
//////////
// MSLUTSTART
//////////
uint8_t Trinamic_TMC2130::set_MSLUTSTART(uint8_t start_sin, uint8_t start_sin90)
{
uint32_t data;
data = ( uint32_t(start_sin90) & TMC_MSLUTSTART_START_SIN90_MASK );
data = data<<TMC_MSLUTSTART_START_SIN90;
data |= ( uint32_t(start_sin) & TMC_MSLUTSTART_START_SIN_MASK );
data &= TMC_MSLUTSTART_MASK;
write_REG(TMC_REG_MSLUTSTART, data);
return _status;
}
//////////
// MSCNT
//////////
uint16_t Trinamic_TMC2130::get_MSCNT()
{
uint32_t data;
read_REG(TMC_REG_MSCNT, &data);
data &= TMC_MSCNT_MASK;
data = uint16_t(data);
return data;
}
//////////
// MSCURACT
//////////
int32_t Trinamic_TMC2130::get_MSCURACT()
{
uint32_t data;
read_REG(TMC_REG_MSCURACT, &data);
data &= TMC_MSCURACT_MASK;
return data;
}
//////////
// CHOPCONF
//////////
uint8_t Trinamic_TMC2130::set_diss2g(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_DISS2G, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_dedge(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_DEDGE, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_intpol(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_INTPOL, value);
return _status;
}
// setting the microstep resolution
uint8_t Trinamic_TMC2130::set_mres(uint16_t value)
{
uint8_t data = 0;
switch(value){
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;
}
set_CHOPCONF(TMC_CHOPCONF_MRES, data);
return _status;
}
uint8_t Trinamic_TMC2130::set_sync(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_SYNC, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_vhighchm(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_VHIGHCHM, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_vhighfs(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_VHIGHFS, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_vsense(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_VSENSE, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_tbl(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_TBL, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_chm(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_CHM, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_rndtf(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_RNDTF, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_disfdcc(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_DISFDCC, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_fd(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_FD, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_hend(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_HEND, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_hstrt(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_HSTRT, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_toff(uint8_t value)
{
set_CHOPCONF(TMC_CHOPCONF_TOFF, value);
return _status;
}
//////////
// COOLCONF
//////////
// alter coolconf
uint8_t Trinamic_TMC2130::alter_COOLCONF(uint32_t data, uint32_t mask)
{
uint32_t newData;
_coolconf = ( _coolconf & ~mask ) | ( data & mask );
write_REG( TMC_REG_COOLCONF, _coolconf );
return _status;
}
// set coolconf
uint8_t Trinamic_TMC2130::set_COOLCONF(uint8_t position, uint8_t value)
{
alter_COOLCONF( uint32_t(value)<<position, TMC_CHOPCONF_MASKS[position]<<position);
return _status;
}
uint8_t Trinamic_TMC2130::set_sfilt(uint8_t value)
{
set_CHOPCONF(TMC_COOLCONF_SFILT, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_sgt(uint8_t value)
{
set_CHOPCONF(TMC_COOLCONF_SGT, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_seimin(uint8_t value)
{
set_CHOPCONF(TMC_COOLCONF_SEIMIN, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_sedn(uint8_t value)
{
set_CHOPCONF(TMC_COOLCONF_SEDN, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_semax(uint8_t value)
{
set_CHOPCONF(TMC_COOLCONF_SEMAX, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_seup(uint8_t value)
{
set_CHOPCONF(TMC_COOLCONF_SEUP, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_semin(uint8_t value)
{
set_CHOPCONF(TMC_COOLCONF_SEMIN, value);
return _status;
}
//////////
// DCCTRL
//////////
uint8_t Trinamic_TMC2130::set_DCCTRL(uint16_t dc_time, uint16_t dc_sg)
{
uint32_t data;
data = ( uint32_t(dc_sg) & TMC_DCCTRL_DC_SG_MASK );
data = data<<TMC_DCCTRL_DC_SG;
data |= ( uint32_t(dc_time) & TMC_DCCTRL_DC_TIME_MASK );
data &= TMC_DCCTRL_MASK;
write_REG(TMC_REG_DCCTRL, data);
return _status;
}
//////////
// PWMCONF
//////////
// alter pwmconf
uint8_t Trinamic_TMC2130::alter_PWMCONF(uint32_t data, uint32_t mask)
{
uint32_t newData;
_pwmconf = ( _pwmconf & ~mask ) | ( data & mask );
write_REG( TMC_REG_PWMCONF, _pwmconf );
return _status;
}
// set pwmconf
uint8_t Trinamic_TMC2130::set_PWMCONF(uint8_t position, uint8_t value)
{
alter_PWMCONF( uint32_t(value)<<position, TMC_CHOPCONF_MASKS[position]<<position );
return _status;
}
uint8_t Trinamic_TMC2130::set_freewheel(uint8_t value)
{
set_PWMCONF(TMC_PWMCONF_FREEWHEEL, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_pwm_symmetric(uint8_t value)
{
set_PWMCONF(TMC_PWMCONF_PWM_SYMMETRIC, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_pwm_autoscale(uint8_t value)
{
set_PWMCONF(TMC_PWMCONF_PWM_AUTOSCALE, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_pwm_freq(uint8_t value)
{
set_PWMCONF(TMC_PWMCONF_PWM_FREQ, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_PWM_GRAD(uint8_t value)
{
set_PWMCONF(TMC_PWMCONF_PWM_GRAD, value);
return _status;
}
uint8_t Trinamic_TMC2130::set_PWM_AMPL(uint8_t value)
{
set_PWMCONF(TMC_PWMCONF_PWM_AMPL, value);
return _status;
}
//////////
// ENCM_CTRL
//////////
uint8_t Trinamic_TMC2130::set_ENCM_CTRL(uint8_t value)
{
uint8_t data;
data = value & TMC_ENCM_CTRL_MASK;
write_REG(TMC_REG_ENCM_CTRL, data);
return _status;
}
//////////
// STATUS
//////////
// check the reset status
boolean Trinamic_TMC2130::isReset()
{
return _status&TMC_SPISTATUS_RESET_MASK ? true : false;
}
// check the error status
boolean Trinamic_TMC2130::isError()
{
return _status&TMC_SPISTATUS_ERROR_MASK ? true : false;
}
// check the stallguard status
boolean Trinamic_TMC2130::isStallguard()
{
return _status&TMC_SPISTATUS_STALLGUARD_MASK ? true : false;
}
// check the standstill status
boolean Trinamic_TMC2130::isStandstill()
{
return _status&TMC_SPISTATUS_STANDSTILL_MASK ? true : false;
}
// get debug messages
String Trinamic_TMC2130::debug()
{
return _debug;
}

View File

@ -0,0 +1,137 @@
/**************************************************************************/
/*!
@file Trinamic_TMC2130.h
@author Moritz Walter
@license GPLv3 (see license.txt)
SPI configuration tool for Trinamic TMC2130 Motor Drivers
@section HISTORY
v0.1 - it works
*/
/**************************************************************************/
#ifndef TRINAMIC_TMC2130_H
#define TRINAMIC_TMC2130_H
#if ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#include <SPI.h>
#include "Trinamic_TMC2130_registers.h"
class Trinamic_TMC2130{
public:
Trinamic_TMC2130(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_I_scale_analog(uint8_t value);
uint8_t set_internal_Rsense(uint8_t value);
uint8_t set_en_pwm_mode(uint8_t value);
uint8_t set_enc_commutation(uint8_t value);
uint8_t set_shaft(uint8_t value);
uint8_t set_diag0_error(uint8_t value);
uint8_t set_diag0_otpw(uint8_t value);
uint8_t set_diag0_stall(uint8_t value);
uint8_t set_diag1_stall(uint8_t value);
uint8_t set_diag1_index(uint8_t value);
uint8_t set_diag1_onstate(uint8_t value);
uint8_t set_diag1_steps_skipped(uint8_t value);
uint8_t set_diag0_int_pushpull(uint8_t value);
uint8_t set_diag1_int_pushpull(uint8_t value);
uint8_t set_small_hysteresis(uint8_t value);
uint8_t set_stop_enable(uint8_t value);
uint8_t set_direct_mode(uint8_t value);
//uint8_t test_mode(uint8_t value);
uint8_t set_IHOLD_IRUN(uint8_t ihold, uint8_t irun, uint8_t iholddelay);
uint8_t set_TPOWERDOWN(uint8_t value);
uint32_t get_TSTEP();
uint8_t set_TPWMTHRS(uint32_t value);
uint8_t set_TCOOLTHRS(uint32_t value);
uint8_t set_THIGH(uint32_t value);
uint8_t set_XDIRECT(uint32_t value);
uint8_t set_XDIRECT(int16_t coil_a, int16_t coil_b);
int32_t get_XDIRECT();
uint8_t set_VDCMIN(int32_t value);
uint8_t set_MSLUT0(uint32_t value);
uint8_t set_MSLUT1(uint32_t value);
uint8_t set_MSLUT2(uint32_t value);
uint8_t set_MSLUT3(uint32_t value);
uint8_t set_MSLUT4(uint32_t value);
uint8_t set_MSLUT5(uint32_t value);
uint8_t set_MSLUT6(uint32_t value);
uint8_t set_MSLUT7(uint32_t value);
uint8_t set_MSLUTSEL(uint32_t value);
uint8_t set_MSLUTSTART(uint8_t start_sin, uint8_t start_sin90);
uint16_t get_MSCNT();
int32_t get_MSCURACT();
uint8_t set_CHOPCONF(uint8_t position, uint8_t value);
uint8_t set_dedge(uint8_t value);
uint8_t set_diss2g(uint8_t value);
uint8_t set_intpol(uint8_t value);
uint8_t set_mres(uint16_t value);
uint8_t set_sync(uint8_t value);
uint8_t set_vhighchm(uint8_t value);
uint8_t set_vhighfs(uint8_t value);
uint8_t set_vsense(uint8_t value);
uint8_t set_tbl(uint8_t value);
uint8_t set_chm(uint8_t value);
uint8_t set_rndtf(uint8_t value);
uint8_t set_disfdcc(uint8_t value);
uint8_t set_fd(uint8_t value);
uint8_t set_hend(uint8_t value);
uint8_t set_hstrt(uint8_t value);
uint8_t set_toff(uint8_t value);
uint8_t alter_COOLCONF(uint32_t data, uint32_t mask);
uint8_t set_COOLCONF(uint8_t position, uint8_t value);
uint8_t set_sfilt(uint8_t value);
uint8_t set_sgt(uint8_t value);
uint8_t set_seimin(uint8_t value);
uint8_t set_sedn(uint8_t value);
uint8_t set_semax(uint8_t value);
uint8_t set_seup(uint8_t value);
uint8_t set_semin(uint8_t value);
uint8_t set_DCCTRL(uint16_t dc_time, uint16_t dc_sg);
uint8_t alter_PWMCONF(uint32_t data, uint32_t mask);
uint8_t set_PWMCONF(uint8_t position, uint8_t value);
uint8_t set_freewheel(uint8_t value);
uint8_t set_pwm_symmetric(uint8_t value);
uint8_t set_pwm_autoscale(uint8_t value);
uint8_t set_pwm_freq(uint8_t value);
uint8_t set_PWM_GRAD(uint8_t value);
uint8_t set_PWM_AMPL(uint8_t value);
uint8_t set_ENCM_CTRL(uint8_t value);
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 // TRINAMIC_TMC2130_H

View File

@ -0,0 +1,319 @@
/**************************************************************************/
/*!
@file Trinamic_TMC2130_registers.h
@author Moritz Walter
@license GPLv3 (see license.txt)
SPI configuration tool for Trinamic TMC2130 Motor Drivers
@section HISTORY
v0.1 - it works
*/
/**************************************************************************/
#ifndef TRINAMIC_TMC2130_REGISTERS_H
#define TRINAMIC_TMC2130_REGISTERS_H
#if ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#include <SPI.h>
// SPI
#define TMC_SPI_CLOCK_DIVIDER SPI_CLOCK_DIV8
#define TMC_SPI_DATA_MODE SPI_MODE3
#define TMC_SPI_BIT_ORDER MSBFIRST
// RW
#define TMC_READ (0x00)
#define TMC_WRITE (0x80)
// SPISTATUS MASKS
#define TMC_SPISTATUS_RESET_MASK (0x01)
#define TMC_SPISTATUS_ERROR_MASK (0x02)
#define TMC_SPISTATUS_STALLGUARD_MASK (0x04)
#define TMC_SPISTATUS_STANDSTILL_MASK (0x08)
// REGISTERS
#define TMC_REG_GCONF (0x00) // RW // 17 // Global configuration flags
#define TMC_REG_GSTAT (0x01) // RC // 3 // Global status flags
#define TMC_REG_IOIN (0x04) // R // 8+8 // Reads the state of all input pins available
#define TMC_REG_IHOLD_IRUN (0x10) // W // 5+5+4 // Driver current control
#define 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 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 TMC_REG_TPWMTHRS (0x13) // W // 20 // Upper velocity threshold for stealthChop voltage PWM mode
#define TMC_REG_TCOOLTHRS (0x14) // W // 20 // Lower threshold velocity for switching on smart energy coolStep and stallGuard feature (unsigned)
#define TMC_REG_THIGH (0x15) // W // 20 // Velocity dependend switching into different chopper mode and fullstepping to maximize torque (unsigned)
#define 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 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 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 TMC_REG_MSLUT1 (0x61) // W // 32 //
#define TMC_REG_MSLUT2 (0x62) // W // 32 //
#define TMC_REG_MSLUT3 (0x63) // W // 32 //
#define TMC_REG_MSLUT4 (0x64) // W // 32 //
#define TMC_REG_MSLUT5 (0x65) // W // 32 //
#define TMC_REG_MSLUT6 (0x66) // W // 32 //
#define TMC_REG_MSLUT7 (0x67) // W // 32 //
#define 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 TMC_REG_MSLUTSTART (0x69) // W // 8+8 //
#define TMC_REG_MSCNT (0x6A) // R // 10 //
#define TMC_REG_MSCURACT (0x6B) // R // 9+9 //
#define TMC_REG_CHOPCONF (0x6C) // RW // 32 //
#define TMC_REG_COOLCONF (0x6D) // W // 25 //
#define TMC_REG_DCCTRL (0x6E) // W // 24 //
#define TMC_REG_DRV_STATUS (0x6F) // R // 22 //
#define TMC_REG_PWMCONF (0x70) // W // 8 //
#define TMC_REG_PWM_SCALE (0x71) // R // 8 //
#define TMC_REG_ENCM_CTRL (0x72) // W // 2 //
#define TMC_REG_LOST_STEPS (0x73) // R // 20 //
// GCONF OFFSETS
// for shifting incoming values to the right register position
#define TMC_GCONF_I_SCALE_ANALOG (0) // 0: Internal, 1: AIN
#define TMC_GCONF_INTERNAL_RSENSE (1) // 0: Normal, 1: Internal
#define TMC_GCONF_EN_PWM_MODE (2) // 0: Disable, 1: Enable
#define TMC_GCONF_ENC_COMMUTATION (3) // 0: Disable, 1: Enable
#define TMC_GCONF_SHAFT (4) // 0: Normal, 1: Invert
#define TMC_GCONF_DIAG0_ERROR (5) // 0: Disable, 1: Enable
#define TMC_GCONF_DIAG0_OTPW (6) // 0: Disable, 1: Enable
#define TMC_GCONF_DIAG0_STALL (7) // 0: Disable, 1: Enable
#define TMC_GCONF_DIAG1_STALL (8) // 0: Disable, 1: Enable
#define TMC_GCONF_DIAG1_INDEX (9) // 0: Disable, 1: Enable
#define TMC_GCONF_DIAG1_ONSTATE (10) // 0: Disable, 1: Enable
#define TMC_GCONF_DIAG1_STEPS_SKIPPED (11) // 0: Disable, 1: Enable
#define TMC_GCONF_DIAG0_INT_PUSHPULL (12) // 0: Open Collector, 1: Push Pull
#define TMC_GCONF_DIAG1_INT_PUSHPULL (13) // 0: Open Collector, 1: Push Pull
#define TMC_GCONF_SMALL_HYSTERESIS (14) // 0: 1/16, 1: 1/32
#define TMC_GCONF_STOP_ENABLE (15) // 0: Normal, 1: Emergency Stop
#define TMC_GCONF_DIRECT_MODE (16) // 0: Normal, 1: XDIRECT
#define 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 TMC_IHOLD (0)
#define TMC_IRUN (8)
#define TMC_IHOLDDELAY (16)
// IHOLD IRUN MASKS
#define TMC_IHOLD_MASK (0b11111UL)
#define TMC_IRUN_MASK (0b11111UL)
#define TMC_IHOLDDELAY_MASK (0b1111UL)
// TPOWERDOWN
// no offsets required
#define TMC_TPOWERDOWN_MASK (0b11111111UL)
// TSTEP
// no offsets required
#define TMC_TSTEP_MASK (0b11111111111111111111UL)
// TPWMTHRS
// no offsets required
#define TMC_TPWMTHRS_MASK (0b11111111111111111111UL)
// TCOOLTHRS
#define TMC_TCOOLTHRS_MASK (0b11111111111111111111UL)
// THIGH
// no offsets required
#define TMC_THIGH_MASK (0b11111111111111111111UL)
// XDIRECT OFFSETS
// for shifting incoming values to the right register position
#define TMC_XDIRECT_COIL_A (0)
#define TMC_XDIRECT_COIL_B (16)
// XDIRECT MASKS
// mask the bits from the values we want to set
#define TMC_XDIRECT_MASK (0xFFFFFFFFUL)
#define TMC_XDIRECT_COIL_A_MASK (0xFFFFUL)
#define TMC_XDIRECT_COIL_B_MASK (0xFFFFUL)
// no offsets required
// needs no mask
// VDCMIN
// no offsets required
#define TMC_VDCMIN_MASK (0b11111111111111111111111UL)
// MSLUT
// no offsets required
// needs no mask
// MSLUTSEL
// no offsets required
// needs no mask
// MSLUTSTART OFFSETS
#define TMC_MSLUTSTART_START_SIN (0)
#define TMC_MSLUTSTART_START_SIN90 (8)
// MSLUTSTART MASKS
#define TMC_MSLUTSTART_MASK (0xFFFFUL)
#define TMC_MSLUTSTART_START_SIN_MASK (0xFF)
#define TMC_MSLUTSTART_START_SIN90_MASK (0xFF)
// MSCNT
// no offsets required
#define TMC_MSCNT_MASK (0b1111111111)
// MSCURACT
// no offsets required
#define TMC_MSCURACT_MASK (0b111111111111111111UL)
// CHOPCONF MASKS
// mask the bits from the values we want to set
const uint32_t 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 TMC_CHOPCONF_DISS2G (30)
#define TMC_CHOPCONF_DEDGE (29)
#define TMC_CHOPCONF_INTPOL (28)
#define TMC_CHOPCONF_MRES (24)
#define TMC_CHOPCONF_SYNC (20)
#define TMC_CHOPCONF_VHIGHCHM (19)
#define TMC_CHOPCONF_VHIGHFS (18)
#define TMC_CHOPCONF_VSENSE (17)
#define TMC_CHOPCONF_TBL (15)
#define TMC_CHOPCONF_CHM (14)
#define TMC_CHOPCONF_RNDTF (13)
#define TMC_CHOPCONF_DISFDCC (12)
#define TMC_CHOPCONF_FD (11)
#define TMC_CHOPCONF_HEND (7)
#define TMC_CHOPCONF_HSTRT (4)
#define TMC_CHOPCONF_TOFF (0)
// COOLCONF BIT OFFSETS
// for shifting incoming values to the right register position
#define TMC_COOLCONF_SFILT (24)
#define TMC_COOLCONF_SGT (16)
#define TMC_COOLCONF_SEIMIN (15)
#define TMC_COOLCONF_SEDN (13)
#define TMC_COOLCONF_SEMAX (8)
#define TMC_COOLCONF_SEUP (5)
#define TMC_COOLCONF_SEMIN (0)
// COOLCONF MASKS
// mask the bits from the values we want to set
const int TMC_COOLCONF_MASKS[] = {
0b1111UL, // 0 TMC_COOLCONF_SEMIN
0b111UL, // 1
0b11UL, // 2
0b1UL, // 3
0b0UL, // 4
0b11UL, // 5 TMC_COOLCONF_SEUP
0b1UL, // 6
0b0UL, // 7
0b1111UL, // 8 TMC_COOLCONF_SEMAX
0b111UL, // 9
0b11UL, // 10
0b1UL, // 11
0b0UL, // 12
0b11UL, // 13 TMC_COOLCONF_SEDN
0b1UL, // 14
0b1UL, // 15 TMC_COOLCONF_SEIMIN
0b1111111UL, // 16 TMC_COOLCONF_SGT
0b111111UL, // 17
0b11111UL, // 18
0b1111UL, // 19
0b111UL, // 20
0b11UL, // 21
0b1UL, // 22
0b0UL, // 23
0b1UL, // 24 TMC_COOLCONF_SFILT
};
// DCCTRL OFFSETS
// for shifting incoming values to the right register position
#define TMC_DCCTRL_DC_TIME (0)
#define TMC_DCCTRL_DC_SG (16)
// DCCTRL MASKS
// mask the bits from the values we want to set
#define TMC_DCCTRL_MASK (0b1111111111UL)
#define TMC_DCCTRL_DC_TIME_MASK (0b11111111UL)
#define TMC_DCCTRL_DC_SG_MASK (0b111111110000001111111111UL)
// PWMCONF OFFSETS
// for shifting incoming values to the right register position
#define TMC_PWMCONF_FREEWHEEL (20)
#define TMC_PWMCONF_PWM_SYMMETRIC (19)
#define TMC_PWMCONF_PWM_AUTOSCALE (18)
#define TMC_PWMCONF_PWM_FREQ (16)
#define TMC_PWMCONF_PWM_GRAD (8)
#define TMC_PWMCONF_PWM_AMPL (0)
// PWMCONF MASKS
// mask the bits from the values we want to set
const int TMC_PWMCONF_MASKS[] = {
0b11111111UL, // 0 TMC_PWMCONF_PWM_AMPL
0b1111111UL, // 1
0b111111UL, // 2
0b11111UL, // 3
0b1111UL, // 4
0b111UL, // 5
0b11UL, // 6
0b1UL, // 7
0b11111111UL, // 8 TMC_PWMCONF_PWM_GRAD
0b1111111UL, // 9
0b111111UL, // 10
0b11111UL, // 11
0b1111UL, // 12
0b111UL, // 13
0b11UL, // 14
0b1UL, // 15
0b11UL, // 16 TMC_PWMCONF_PWM_FREQ
0b1UL, // 17
0b1UL, // 18 TMC_PWMCONF_PWM_AUTOSCALE
0b1UL, // 19 TMC_PWMCONF_PWM_SYMMETRIC
0b11UL, // 20 TMC_PWMCONF_FREEWHEEL
0b1UL, // 21
};
// ENCM_CTRL MASK
// mask the bits from the values we want to set
#define TMC_ENCM_CTRL_MASK (0b11);
#endif // TRINAMIC_TMC2130_REGISTERS_H

View File

@ -581,46 +581,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 +708,13 @@ void startServo()
}
#if defined(FARMDUINO_EXP_V20)
/**/
//Trinamic_TMC2130 controllerTMC2130_X(X_CHIP_SELECT);
//Trinamic_TMC2130 controllerTMC2130_Y(Y_CHIP_SELECT);
//Trinamic_TMC2130 controllerTMC2130_Z(Z_CHIP_SELECT);
//Trinamic_TMC2130 controllerTMC2130_E(E_CHIP_SELECT);
void loadTMC2130drivers()
{
Serial.print(COMM_REPORT_COMMENT);
@ -755,150 +722,38 @@ 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();
Trinamic_TMC2130 controllerTMC2130_X = Trinamic_TMC2130(X_CHIP_SELECT);
Trinamic_TMC2130 controllerTMC2130_Y = Trinamic_TMC2130(Y_CHIP_SELECT);
Trinamic_TMC2130 controllerTMC2130_Z = Trinamic_TMC2130(Z_CHIP_SELECT);
Trinamic_TMC2130 controllerTMC2130_E = Trinamic_TMC2130(E_CHIP_SELECT);
TMC2130X = &controllerTMC2130_X;
TMC2130Y = &controllerTMC2130_Y;
TMC2130Z = &controllerTMC2130_Z;
TMC2130E = &controllerTMC2130_E;
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
}
void loadTMC2130parameters()
{
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();
}
#endif

View File

@ -15,8 +15,8 @@ void setup()
#if defined(FARMDUINO_EXP_V20)
loadTMC2130drivers();
//loadTMC2130parameters();
startupTmc();
loadTMC2130parameters();
#endif
loadMovementSetting();

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="Trinamic\Trinamic_TMC2130.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="Trinamic\Trinamic_TMC2130.h" />
<ClInclude Include="Trinamic\Trinamic_TMC2130_registers.h" />
<ClInclude Include="__vm\.farmbot-arduino-controller.vsarduino.h" />
<ClInclude Include="__vm\.src.vsarduino.h" />
</ItemGroup>

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="Trinamic\Trinamic_TMC2130.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="Trinamic\Trinamic_TMC2130.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="Trinamic\Trinamic_TMC2130_registers.h">
<Filter>Header Files</Filter>
</ClInclude>
</ItemGroup>