Merge pull request #2 from MarlinFirmware/Development

actual
This commit is contained in:
Wurstnase 2015-03-11 23:47:41 +01:00
commit 3898ace246
90 changed files with 36057 additions and 1004 deletions

View file

@ -13,6 +13,8 @@ install:
- sudo apt-get update -q
- sudo apt-get install arduino
before_script:
# copy TMC and L6470 libraries to arduino dir, as conditional includes do not work in .ino files
- sudo cp -r ArduinoAddons/Arduino_1.x.x/libraries/ /usr/share/arduino
# add U8glib, LiquidCrystal_I2C & LiquidTWI2 libraries
- sudo unzip u8glib_arduino_v1.17.zip -d /usr/share/arduino/libraries/
- cd /usr/share/arduino/libraries/

View file

@ -0,0 +1,723 @@
////////////////////////////////////////////////////////////
//ORIGINAL CODE 12/12/2011- Mike Hord, SparkFun Electronics
//LIBRARY Created by Adam Meyer of bildr Aug 18th 2012
//Released as MIT license
////////////////////////////////////////////////////////////
#include <Arduino.h>
#include "L6470.h"
#include <SPI.h>
#define ENABLE_RESET_PIN 0
#define K_VALUE 100
L6470::L6470(int SSPin){
_SSPin = SSPin;
// Serial.begin(9600);
}
void L6470::init(int k_value){
// This is the generic initialization function to set up the Arduino to
// communicate with the dSPIN chip.
// set up the input/output pins for the application.
pinMode(SLAVE_SELECT_PIN, OUTPUT); // The SPI peripheral REQUIRES the hardware SS pin-
// pin 10- to be an output. This is in here just
// in case some future user makes something other
// than pin 10 the SS pin.
pinMode(_SSPin, OUTPUT);
digitalWrite(_SSPin, HIGH);
pinMode(MOSI, OUTPUT);
pinMode(MISO, INPUT);
pinMode(SCK, OUTPUT);
pinMode(BUSYN, INPUT);
#if (ENABLE_RESET_PIN == 1)
pinMode(RESET, OUTPUT);
// reset the dSPIN chip. This could also be accomplished by
// calling the "L6470::ResetDev()" function after SPI is initialized.
digitalWrite(RESET, HIGH);
delay(10);
digitalWrite(RESET, LOW);
delay(10);
digitalWrite(RESET, HIGH);
delay(10);
#endif
// initialize SPI for the dSPIN chip's needs:
// most significant bit first,
// SPI clock not to exceed 5MHz,
// SPI_MODE3 (clock idle high, latch data on rising edge of clock)
SPI.begin();
SPI.setBitOrder(MSBFIRST);
SPI.setClockDivider(SPI_CLOCK_DIV16); // or 2, 8, 16, 32, 64
SPI.setDataMode(SPI_MODE3);
// First things first: let's check communications. The CONFIG register should
// power up to 0x2E88, so we can use that to check the communications.
if (GetParam(CONFIG) == 0x2E88){
//Serial.println('good to go');
}
else{
//Serial.println('Comm issue');
}
#if (ENABLE_RESET_PIN == 0)
resetDev();
#endif
// First, let's set the step mode register:
// - SYNC_EN controls whether the BUSY/SYNC pin reflects the step
// frequency or the BUSY status of the chip. We want it to be the BUSY
// status.
// - STEP_SEL_x is the microstepping rate- we'll go full step.
// - SYNC_SEL_x is the ratio of (micro)steps to toggles on the
// BUSY/SYNC pin (when that pin is used for SYNC). Make it 1:1, despite
// not using that pin.
//SetParam(STEP_MODE, !SYNC_EN | STEP_SEL_1 | SYNC_SEL_1);
SetParam(KVAL_RUN, k_value);
SetParam(KVAL_ACC, k_value);
SetParam(KVAL_DEC, k_value);
SetParam(KVAL_HOLD, k_value);
// Set up the CONFIG register as follows:
// PWM frequency divisor = 1
// PWM frequency multiplier = 2 (62.5kHz PWM frequency)
// Slew rate is 290V/us
// Do NOT shut down bridges on overcurrent
// Disable motor voltage compensation
// Hard stop on switch low
// 16MHz internal oscillator, nothing on output
SetParam(CONFIG, CONFIG_PWM_DIV_1 | CONFIG_PWM_MUL_2 | CONFIG_SR_290V_us| CONFIG_OC_SD_DISABLE | CONFIG_VS_COMP_DISABLE | CONFIG_SW_HARD_STOP | CONFIG_INT_16MHZ);
// Configure the RUN KVAL. This defines the duty cycle of the PWM of the bridges
// during running. 0xFF means that they are essentially NOT PWMed during run; this
// MAY result in more power being dissipated than you actually need for the task.
// Setting this value too low may result in failure to turn.
// There are ACC, DEC, and HOLD KVAL registers as well; you may need to play with
// those values to get acceptable performance for a given application.
//SetParam(KVAL_RUN, 0xFF);
// Calling GetStatus() clears the UVLO bit in the status register, which is set by
// default on power-up. The driver may not run without that bit cleared by this
// read operation.
getStatus();
hardStop(); //engage motors
}
boolean L6470::isBusy(){
int status = getStatus();
return !((status >> 1) & 0b1);
}
void L6470::setMicroSteps(int microSteps){
byte stepVal = 0;
for(stepVal = 0; stepVal < 8; stepVal++){
if(microSteps == 1) break;
microSteps = microSteps >> 1;
}
SetParam(STEP_MODE, !SYNC_EN | stepVal | SYNC_SEL_1);
}
void L6470::setThresholdSpeed(float thresholdSpeed){
// Configure the FS_SPD register- this is the speed at which the driver ceases
// microstepping and goes to full stepping. FSCalc() converts a value in steps/s
// to a value suitable for this register; to disable full-step switching, you
// can pass 0x3FF to this register.
if(thresholdSpeed == 0.0){
SetParam(FS_SPD, 0x3FF);
}
else{
SetParam(FS_SPD, FSCalc(thresholdSpeed));
}
}
void L6470::setCurrent(int current){}
void L6470::setMaxSpeed(int speed){
// Configure the MAX_SPEED register- this is the maximum number of (micro)steps per
// second allowed. You'll want to mess around with your desired application to see
// how far you can push it before the motor starts to slip. The ACTUAL parameter
// passed to this function is in steps/tick; MaxSpdCalc() will convert a number of
// steps/s into an appropriate value for this function. Note that for any move or
// goto type function where no speed is specified, this value will be used.
SetParam(MAX_SPEED, MaxSpdCalc(speed));
}
void L6470::setMinSpeed(int speed){
// Configure the MAX_SPEED register- this is the maximum number of (micro)steps per
// second allowed. You'll want to mess around with your desired application to see
// how far you can push it before the motor starts to slip. The ACTUAL parameter
// passed to this function is in steps/tick; MaxSpdCalc() will convert a number of
// steps/s into an appropriate value for this function. Note that for any move or
// goto type function where no speed is specified, this value will be used.
SetParam(MIN_SPEED, MinSpdCalc(speed));
}
void L6470::setAcc(float acceleration){
// Configure the acceleration rate, in steps/tick/tick. There is also a DEC register;
// both of them have a function (AccCalc() and DecCalc() respectively) that convert
// from steps/s/s into the appropriate value for the register. Writing ACC to 0xfff
// sets the acceleration and deceleration to 'infinite' (or as near as the driver can
// manage). If ACC is set to 0xfff, DEC is ignored. To get infinite deceleration
// without infinite acceleration, only hard stop will work.
unsigned long accelerationBYTES = AccCalc(acceleration);
SetParam(ACC, accelerationBYTES);
}
void L6470::setDec(float deceleration){
unsigned long decelerationBYTES = DecCalc(deceleration);
SetParam(DEC, decelerationBYTES);
}
long L6470::getPos(){
unsigned long position = GetParam(ABS_POS);
return convert(position);
}
float L6470::getSpeed(){
/*
SPEED
The SPEED register contains the current motor speed, expressed in step/tick (format unsigned fixed point 0.28).
In order to convert the SPEED value in step/s the following formula can be used:
Equation 4
where SPEED is the integer number stored into the register and tick is 250 ns.
The available range is from 0 to 15625 step/s with a resolution of 0.015 step/s.
Note: The range effectively available to the user is limited by the MAX_SPEED parameter.
*/
return (float) GetParam(SPEED);
//return (float) speed * pow(8, -22);
//return FSCalc(speed); NEEDS FIX
}
void L6470::setOverCurrent(unsigned int ma_current){
// Configure the overcurrent detection threshold.
byte OCValue = floor(ma_current / 375);
if(OCValue > 0x0F)OCValue = 0x0F;
SetParam(OCD_TH, OCValue);
}
void L6470::setStallCurrent(float ma_current){
byte STHValue = (byte)floor(ma_current / 31.25);
if(STHValue > 0x80)STHValue = 0x80;
if(STHValue < 0)STHValue = 0;
SetParam(STALL_TH, STHValue);
}
void L6470::SetLowSpeedOpt(boolean enable){
// Enable or disable the low-speed optimization option. If enabling,
// the other 12 bits of the register will be automatically zero.
// When disabling, the value will have to be explicitly written by
// the user with a SetParam() call. See the datasheet for further
// information about low-speed optimization.
Xfer(SET_PARAM | MIN_SPEED);
if (enable) Param(0x1000, 13);
else Param(0, 13);
}
void L6470::run(byte dir, float spd){
// RUN sets the motor spinning in a direction (defined by the constants
// FWD and REV). Maximum speed and minimum speed are defined
// by the MAX_SPEED and MIN_SPEED registers; exceeding the FS_SPD value
// will switch the device into full-step mode.
// The SpdCalc() function is provided to convert steps/s values into
// appropriate integer values for this function.
unsigned long speedVal = SpdCalc(spd);
Xfer(RUN | dir);
if (speedVal > 0xFFFFF) speedVal = 0xFFFFF;
Xfer((byte)(speedVal >> 16));
Xfer((byte)(speedVal >> 8));
Xfer((byte)(speedVal));
}
void L6470::Step_Clock(byte dir){
// STEP_CLOCK puts the device in external step clocking mode. When active,
// pin 25, STCK, becomes the step clock for the device, and steps it in
// the direction (set by the FWD and REV constants) imposed by the call
// of this function. Motion commands (RUN, MOVE, etc) will cause the device
// to exit step clocking mode.
Xfer(STEP_CLOCK | dir);
}
void L6470::move(long n_step){
// MOVE will send the motor n_step steps (size based on step mode) in the
// direction imposed by dir (FWD or REV constants may be used). The motor
// will accelerate according the acceleration and deceleration curves, and
// will run at MAX_SPEED. Stepping mode will adhere to FS_SPD value, as well.
byte dir;
if(n_step >= 0){
dir = FWD;
}
else{
dir = REV;
}
long n_stepABS = abs(n_step);
Xfer(MOVE | dir); //set direction
if (n_stepABS > 0x3FFFFF) n_step = 0x3FFFFF;
Xfer((byte)(n_stepABS >> 16));
Xfer((byte)(n_stepABS >> 8));
Xfer((byte)(n_stepABS));
}
void L6470::goTo(long pos){
// GOTO operates much like MOVE, except it produces absolute motion instead
// of relative motion. The motor will be moved to the indicated position
// in the shortest possible fashion.
Xfer(GOTO);
if (pos > 0x3FFFFF) pos = 0x3FFFFF;
Xfer((byte)(pos >> 16));
Xfer((byte)(pos >> 8));
Xfer((byte)(pos));
}
void L6470::goTo_DIR(byte dir, long pos){
// Same as GOTO, but with user constrained rotational direction.
Xfer(GOTO_DIR);
if (pos > 0x3FFFFF) pos = 0x3FFFFF;
Xfer((byte)(pos >> 16));
Xfer((byte)(pos >> 8));
Xfer((byte)(pos));
}
void L6470::goUntil(byte act, byte dir, unsigned long spd){
// GoUntil will set the motor running with direction dir (REV or
// FWD) until a falling edge is detected on the SW pin. Depending
// on bit SW_MODE in CONFIG, either a hard stop or a soft stop is
// performed at the falling edge, and depending on the value of
// act (either RESET or COPY) the value in the ABS_POS register is
// either RESET to 0 or COPY-ed into the MARK register.
Xfer(GO_UNTIL | act | dir);
if (spd > 0x3FFFFF) spd = 0x3FFFFF;
Xfer((byte)(spd >> 16));
Xfer((byte)(spd >> 8));
Xfer((byte)(spd));
}
void L6470::releaseSW(byte act, byte dir){
// Similar in nature to GoUntil, ReleaseSW produces motion at the
// higher of two speeds: the value in MIN_SPEED or 5 steps/s.
// The motor continues to run at this speed until a rising edge
// is detected on the switch input, then a hard stop is performed
// and the ABS_POS register is either COPY-ed into MARK or RESET to
// 0, depending on whether RESET or COPY was passed to the function
// for act.
Xfer(RELEASE_SW | act | dir);
}
void L6470::goHome(){
// GoHome is equivalent to GoTo(0), but requires less time to send.
// Note that no direction is provided; motion occurs through shortest
// path. If a direction is required, use GoTo_DIR().
Xfer(GO_HOME);
}
void L6470::goMark(){
// GoMark is equivalent to GoTo(MARK), but requires less time to send.
// Note that no direction is provided; motion occurs through shortest
// path. If a direction is required, use GoTo_DIR().
Xfer(GO_MARK);
}
void L6470::setMark(long value){
Xfer(MARK);
if (value > 0x3FFFFF) value = 0x3FFFFF;
if (value < -0x3FFFFF) value = -0x3FFFFF;
Xfer((byte)(value >> 16));
Xfer((byte)(value >> 8));
Xfer((byte)(value));
}
void L6470::setMark(){
long value = getPos();
Xfer(MARK);
if (value > 0x3FFFFF) value = 0x3FFFFF;
if (value < -0x3FFFFF) value = -0x3FFFFF;
Xfer((byte)(value >> 16));
Xfer((byte)(value >> 8));
Xfer((byte)(value));
}
void L6470::setAsHome(){
// Sets the ABS_POS register to 0, effectively declaring the current
// position to be "HOME".
Xfer(RESET_POS);
}
void L6470::resetDev(){
// Reset device to power up conditions. Equivalent to toggling the STBY
// pin or cycling power.
Xfer(RESET_DEVICE);
}
void L6470::softStop(){
// Bring the motor to a halt using the deceleration curve.
Xfer(SOFT_STOP);
}
void L6470::hardStop(){
// Stop the motor right away. No deceleration.
Xfer(HARD_STOP);
}
void L6470::softFree(){
// Decelerate the motor and disengage
Xfer(SOFT_HIZ);
}
void L6470::free(){
// disengage the motor immediately with no deceleration.
Xfer(HARD_HIZ);
}
int L6470::getStatus(){
// Fetch and return the 16-bit value in the STATUS register. Resets
// any warning flags and exits any error states. Using GetParam()
// to read STATUS does not clear these values.
int temp = 0;
Xfer(GET_STATUS);
temp = Xfer(0)<<8;
temp |= Xfer(0);
return temp;
}
unsigned long L6470::AccCalc(float stepsPerSecPerSec){
// The value in the ACC register is [(steps/s/s)*(tick^2)]/(2^-40) where tick is
// 250ns (datasheet value)- 0x08A on boot.
// Multiply desired steps/s/s by .137438 to get an appropriate value for this register.
// This is a 12-bit value, so we need to make sure the value is at or below 0xFFF.
float temp = stepsPerSecPerSec * 0.137438;
if( (unsigned long) long(temp) > 0x00000FFF) return 0x00000FFF;
else return (unsigned long) long(temp);
}
unsigned long L6470::DecCalc(float stepsPerSecPerSec){
// The calculation for DEC is the same as for ACC. Value is 0x08A on boot.
// This is a 12-bit value, so we need to make sure the value is at or below 0xFFF.
float temp = stepsPerSecPerSec * 0.137438;
if( (unsigned long) long(temp) > 0x00000FFF) return 0x00000FFF;
else return (unsigned long) long(temp);
}
unsigned long L6470::MaxSpdCalc(float stepsPerSec){
// The value in the MAX_SPD register is [(steps/s)*(tick)]/(2^-18) where tick is
// 250ns (datasheet value)- 0x041 on boot.
// Multiply desired steps/s by .065536 to get an appropriate value for this register
// This is a 10-bit value, so we need to make sure it remains at or below 0x3FF
float temp = stepsPerSec * .065536;
if( (unsigned long) long(temp) > 0x000003FF) return 0x000003FF;
else return (unsigned long) long(temp);
}
unsigned long L6470::MinSpdCalc(float stepsPerSec){
// The value in the MIN_SPD register is [(steps/s)*(tick)]/(2^-24) where tick is
// 250ns (datasheet value)- 0x000 on boot.
// Multiply desired steps/s by 4.1943 to get an appropriate value for this register
// This is a 12-bit value, so we need to make sure the value is at or below 0xFFF.
float temp = stepsPerSec * 4.1943;
if( (unsigned long) long(temp) > 0x00000FFF) return 0x00000FFF;
else return (unsigned long) long(temp);
}
unsigned long L6470::FSCalc(float stepsPerSec){
// The value in the FS_SPD register is ([(steps/s)*(tick)]/(2^-18))-0.5 where tick is
// 250ns (datasheet value)- 0x027 on boot.
// Multiply desired steps/s by .065536 and subtract .5 to get an appropriate value for this register
// This is a 10-bit value, so we need to make sure the value is at or below 0x3FF.
float temp = (stepsPerSec * .065536)-.5;
if( (unsigned long) long(temp) > 0x000003FF) return 0x000003FF;
else return (unsigned long) long(temp);
}
unsigned long L6470::IntSpdCalc(float stepsPerSec){
// The value in the INT_SPD register is [(steps/s)*(tick)]/(2^-24) where tick is
// 250ns (datasheet value)- 0x408 on boot.
// Multiply desired steps/s by 4.1943 to get an appropriate value for this register
// This is a 14-bit value, so we need to make sure the value is at or below 0x3FFF.
float temp = stepsPerSec * 4.1943;
if( (unsigned long) long(temp) > 0x00003FFF) return 0x00003FFF;
else return (unsigned long) long(temp);
}
unsigned long L6470::SpdCalc(float stepsPerSec){
// When issuing RUN command, the 20-bit speed is [(steps/s)*(tick)]/(2^-28) where tick is
// 250ns (datasheet value).
// Multiply desired steps/s by 67.106 to get an appropriate value for this register
// This is a 20-bit value, so we need to make sure the value is at or below 0xFFFFF.
float temp = stepsPerSec * 67.106;
if( (unsigned long) long(temp) > 0x000FFFFF) return 0x000FFFFF;
else return (unsigned long)temp;
}
unsigned long L6470::Param(unsigned long value, byte bit_len){
// Generalization of the subsections of the register read/write functionality.
// We want the end user to just write the value without worrying about length,
// so we pass a bit length parameter from the calling function.
unsigned long ret_val=0; // We'll return this to generalize this function
// for both read and write of registers.
byte byte_len = bit_len/8; // How many BYTES do we have?
if (bit_len%8 > 0) byte_len++; // Make sure not to lose any partial byte values.
// Let's make sure our value has no spurious bits set, and if the value was too
// high, max it out.
unsigned long mask = 0xffffffff >> (32-bit_len);
if (value > mask) value = mask;
// The following three if statements handle the various possible byte length
// transfers- it'll be no less than 1 but no more than 3 bytes of data.
// L6470::Xfer() sends a byte out through SPI and returns a byte received
// over SPI- when calling it, we typecast a shifted version of the masked
// value, then we shift the received value back by the same amount and
// store it until return time.
if (byte_len == 3) {
ret_val |= long(Xfer((byte)(value>>16))) << 16;
//Serial.println(ret_val, HEX);
}
if (byte_len >= 2) {
ret_val |= long(Xfer((byte)(value>>8))) << 8;
//Serial.println(ret_val, HEX);
}
if (byte_len >= 1) {
ret_val |= Xfer((byte)value);
//Serial.println(ret_val, HEX);
}
// Return the received values. Mask off any unnecessary bits, just for
// the sake of thoroughness- we don't EXPECT to see anything outside
// the bit length range but better to be safe than sorry.
return (ret_val & mask);
}
byte L6470::Xfer(byte data){
// This simple function shifts a byte out over SPI and receives a byte over
// SPI. Unusually for SPI devices, the dSPIN requires a toggling of the
// CS (slaveSelect) pin after each byte sent. That makes this function
// a bit more reasonable, because we can include more functionality in it.
byte data_out;
digitalWrite(_SSPin,LOW);
// SPI.transfer() both shifts a byte out on the MOSI pin AND receives a
// byte in on the MISO pin.
data_out = SPI.transfer(data);
digitalWrite(_SSPin,HIGH);
return data_out;
}
void L6470::SetParam(byte param, unsigned long value){
Xfer(SET_PARAM | param);
ParamHandler(param, value);
}
unsigned long L6470::GetParam(byte param){
// Realize the "get parameter" function, to read from the various registers in
// the dSPIN chip.
Xfer(GET_PARAM | param);
return ParamHandler(param, 0);
}
long L6470::convert(unsigned long val){
//convert 22bit 2s comp to signed long
int MSB = val >> 21;
val = val << 11;
val = val >> 11;
if(MSB == 1) val = val | 0b11111111111000000000000000000000;
return val;
}
unsigned long L6470::ParamHandler(byte param, unsigned long value){
// Much of the functionality between "get parameter" and "set parameter" is
// very similar, so we deal with that by putting all of it in one function
// here to save memory space and simplify the program.
unsigned long ret_val = 0; // This is a temp for the value to return.
// This switch structure handles the appropriate action for each register.
// This is necessary since not all registers are of the same length, either
// bit-wise or byte-wise, so we want to make sure we mask out any spurious
// bits and do the right number of transfers. That is handled by the dSPIN_Param()
// function, in most cases, but for 1-byte or smaller transfers, we call
// Xfer() directly.
switch (param)
{
// ABS_POS is the current absolute offset from home. It is a 22 bit number expressed
// in two's complement. At power up, this value is 0. It cannot be written when
// the motor is running, but at any other time, it can be updated to change the
// interpreted position of the motor.
case ABS_POS:
ret_val = Param(value, 22);
break;
// EL_POS is the current electrical position in the step generation cycle. It can
// be set when the motor is not in motion. Value is 0 on power up.
case EL_POS:
ret_val = Param(value, 9);
break;
// MARK is a second position other than 0 that the motor can be told to go to. As
// with ABS_POS, it is 22-bit two's complement. Value is 0 on power up.
case MARK:
ret_val = Param(value, 22);
break;
// SPEED contains information about the current speed. It is read-only. It does
// NOT provide direction information.
case SPEED:
ret_val = Param(0, 20);
break;
// ACC and DEC set the acceleration and deceleration rates. Set ACC to 0xFFF
// to get infinite acceleration/decelaeration- there is no way to get infinite
// deceleration w/o infinite acceleration (except the HARD STOP command).
// Cannot be written while motor is running. Both default to 0x08A on power up.
// AccCalc() and DecCalc() functions exist to convert steps/s/s values into
// 12-bit values for these two registers.
case ACC:
ret_val = Param(value, 12);
break;
case DEC:
ret_val = Param(value, 12);
break;
// MAX_SPEED is just what it says- any command which attempts to set the speed
// of the motor above this value will simply cause the motor to turn at this
// speed. Value is 0x041 on power up.
// MaxSpdCalc() function exists to convert steps/s value into a 10-bit value
// for this register.
case MAX_SPEED:
ret_val = Param(value, 10);
break;
// MIN_SPEED controls two things- the activation of the low-speed optimization
// feature and the lowest speed the motor will be allowed to operate at. LSPD_OPT
// is the 13th bit, and when it is set, the minimum allowed speed is automatically
// set to zero. This value is 0 on startup.
// MinSpdCalc() function exists to convert steps/s value into a 12-bit value for this
// register. SetLowSpeedOpt() function exists to enable/disable the optimization feature.
case MIN_SPEED:
ret_val = Param(value, 12);
break;
// FS_SPD register contains a threshold value above which microstepping is disabled
// and the dSPIN operates in full-step mode. Defaults to 0x027 on power up.
// FSCalc() function exists to convert steps/s value into 10-bit integer for this
// register.
case FS_SPD:
ret_val = Param(value, 10);
break;
// KVAL is the maximum voltage of the PWM outputs. These 8-bit values are ratiometric
// representations: 255 for full output voltage, 128 for half, etc. Default is 0x29.
// The implications of different KVAL settings is too complex to dig into here, but
// it will usually work to max the value for RUN, ACC, and DEC. Maxing the value for
// HOLD may result in excessive power dissipation when the motor is not running.
case KVAL_HOLD:
ret_val = Xfer((byte)value);
break;
case KVAL_RUN:
ret_val = Xfer((byte)value);
break;
case KVAL_ACC:
ret_val = Xfer((byte)value);
break;
case KVAL_DEC:
ret_val = Xfer((byte)value);
break;
// INT_SPD, ST_SLP, FN_SLP_ACC and FN_SLP_DEC are all related to the back EMF
// compensation functionality. Please see the datasheet for details of this
// function- it is too complex to discuss here. Default values seem to work
// well enough.
case INT_SPD:
ret_val = Param(value, 14);
break;
case ST_SLP:
ret_val = Xfer((byte)value);
break;
case FN_SLP_ACC:
ret_val = Xfer((byte)value);
break;
case FN_SLP_DEC:
ret_val = Xfer((byte)value);
break;
// K_THERM is motor winding thermal drift compensation. Please see the datasheet
// for full details on operation- the default value should be okay for most users.
case K_THERM:
ret_val = Xfer((byte)value & 0x0F);
break;
// ADC_OUT is a read-only register containing the result of the ADC measurements.
// This is less useful than it sounds; see the datasheet for more information.
case ADC_OUT:
ret_val = Xfer(0);
break;
// Set the overcurrent threshold. Ranges from 375mA to 6A in steps of 375mA.
// A set of defined constants is provided for the user's convenience. Default
// value is 3.375A- 0x08. This is a 4-bit value.
case OCD_TH:
ret_val = Xfer((byte)value & 0x0F);
break;
// Stall current threshold. Defaults to 0x40, or 2.03A. Value is from 31.25mA to
// 4A in 31.25mA steps. This is a 7-bit value.
case STALL_TH:
ret_val = Xfer((byte)value & 0x7F);
break;
// STEP_MODE controls the microstepping settings, as well as the generation of an
// output signal from the dSPIN. Bits 2:0 control the number of microsteps per
// step the part will generate. Bit 7 controls whether the BUSY/SYNC pin outputs
// a BUSY signal or a step synchronization signal. Bits 6:4 control the frequency
// of the output signal relative to the full-step frequency; see datasheet for
// that relationship as it is too complex to reproduce here.
// Most likely, only the microsteps per step value will be needed; there is a set
// of constants provided for ease of use of these values.
case STEP_MODE:
ret_val = Xfer((byte)value);
break;
// ALARM_EN controls which alarms will cause the FLAG pin to fall. A set of constants
// is provided to make this easy to interpret. By default, ALL alarms will trigger the
// FLAG pin.
case ALARM_EN:
ret_val = Xfer((byte)value);
break;
// CONFIG contains some assorted configuration bits and fields. A fairly comprehensive
// set of reasonably self-explanatory constants is provided, but users should refer
// to the datasheet before modifying the contents of this register to be certain they
// understand the implications of their modifications. Value on boot is 0x2E88; this
// can be a useful way to verify proper start up and operation of the dSPIN chip.
case CONFIG:
ret_val = Param(value, 16);
break;
// STATUS contains read-only information about the current condition of the chip. A
// comprehensive set of constants for masking and testing this register is provided, but
// users should refer to the datasheet to ensure that they fully understand each one of
// the bits in the register.
case STATUS: // STATUS is a read-only register
ret_val = Param(0, 16);
break;
default:
ret_val = Xfer((byte)(value));
break;
}
return ret_val;
}

View file

@ -0,0 +1,286 @@
////////////////////////////////////////////////////////////
//ORIGINAL CODE 12/12/2011- Mike Hord, SparkFun Electronics
//LIBRARY Created by Adam Meyer of bildr Aug 18th 2012
//Released as MIT license
////////////////////////////////////////////////////////////
#ifndef L6470_h
#define L6470_h
#include <Arduino.h>
#include <SPI.h>
#define SLAVE_SELECT_PIN 38 // Wire this to the CSN pin
// #define RESET 6 // Wire this to the STBY line
#define BUSYN 7 // Wire this to the BSYN line
// constant definitions for overcurrent thresholds. Write these values to
// register dSPIN_OCD_TH to set the level at which an overcurrent even occurs.
#define OCD_TH_375mA 0x00
#define OCD_TH_750mA 0x01
#define OCD_TH_1125mA 0x02
#define OCD_TH_1500mA 0x03
#define OCD_TH_1875mA 0x04
#define OCD_TH_2250mA 0x05
#define OCD_TH_2625mA 0x06
#define OCD_TH_3000mA 0x07
#define OCD_TH_3375mA 0x08
#define OCD_TH_3750mA 0x09
#define OCD_TH_4125mA 0x0A
#define OCD_TH_4500mA 0x0B
#define OCD_TH_4875mA 0x0C
#define OCD_TH_5250mA 0x0D
#define OCD_TH_5625mA 0x0E
#define OCD_TH_6000mA 0x0F
// STEP_MODE option values.
// First comes the "microsteps per step" options...
#define STEP_MODE_STEP_SEL 0x07 // Mask for these bits only.
#define STEP_SEL_1 0x00
#define STEP_SEL_1_2 0x01
#define STEP_SEL_1_4 0x02
#define STEP_SEL_1_8 0x03
#define STEP_SEL_1_16 0x04
#define STEP_SEL_1_32 0x05
#define STEP_SEL_1_64 0x06
#define STEP_SEL_1_128 0x07
// ...next, define the SYNC_EN bit. When set, the BUSYN pin will instead
// output a clock related to the full-step frequency as defined by the
// SYNC_SEL bits below.
#define STEP_MODE_SYNC_EN 0x80 // Mask for this bit
#define SYNC_EN 0x80
// ...last, define the SYNC_SEL modes. The clock output is defined by
// the full-step frequency and the value in these bits- see the datasheet
// for a matrix describing that relationship (page 46).
#define STEP_MODE_SYNC_SEL 0x70
#define SYNC_SEL_1_2 0x00
#define SYNC_SEL_1 0x10
#define SYNC_SEL_2 0x20
#define SYNC_SEL_4 0x30
#define SYNC_SEL_8 0x40
#define SYNC_SEL_16 0x50
#define SYNC_SEL_32 0x60
#define SYNC_SEL_64 0x70
// Bit names for the ALARM_EN register.
// Each of these bits defines one potential alarm condition.
// When one of these conditions occurs and the respective bit in ALARM_EN is set,
// the FLAG pin will go low. The register must be queried to determine which event
// caused the alarm.
#define ALARM_EN_OVERCURRENT 0x01
#define ALARM_EN_THERMAL_SHUTDOWN 0x02
#define ALARM_EN_THERMAL_WARNING 0x04
#define ALARM_EN_UNDER_VOLTAGE 0x08
#define ALARM_EN_STALL_DET_A 0x10
#define ALARM_EN_STALL_DET_B 0x20
#define ALARM_EN_SW_TURN_ON 0x40
#define ALARM_EN_WRONG_NPERF_CMD 0x80
// CONFIG register renames.
// Oscillator options.
// The dSPIN needs to know what the clock frequency is because it uses that for some
// calculations during operation.
#define CONFIG_OSC_SEL 0x000F // Mask for this bit field.
#define CONFIG_INT_16MHZ 0x0000 // Internal 16MHz, no output
#define CONFIG_INT_16MHZ_OSCOUT_2MHZ 0x0008 // Default; internal 16MHz, 2MHz output
#define CONFIG_INT_16MHZ_OSCOUT_4MHZ 0x0009 // Internal 16MHz, 4MHz output
#define CONFIG_INT_16MHZ_OSCOUT_8MHZ 0x000A // Internal 16MHz, 8MHz output
#define CONFIG_INT_16MHZ_OSCOUT_16MHZ 0x000B // Internal 16MHz, 16MHz output
#define CONFIG_EXT_8MHZ_XTAL_DRIVE 0x0004 // External 8MHz crystal
#define CONFIG_EXT_16MHZ_XTAL_DRIVE 0x0005 // External 16MHz crystal
#define CONFIG_EXT_24MHZ_XTAL_DRIVE 0x0006 // External 24MHz crystal
#define CONFIG_EXT_32MHZ_XTAL_DRIVE 0x0007 // External 32MHz crystal
#define CONFIG_EXT_8MHZ_OSCOUT_INVERT 0x000C // External 8MHz crystal, output inverted
#define CONFIG_EXT_16MHZ_OSCOUT_INVERT 0x000D // External 16MHz crystal, output inverted
#define CONFIG_EXT_24MHZ_OSCOUT_INVERT 0x000E // External 24MHz crystal, output inverted
#define CONFIG_EXT_32MHZ_OSCOUT_INVERT 0x000F // External 32MHz crystal, output inverted
// Configure the functionality of the external switch input
#define CONFIG_SW_MODE 0x0010 // Mask for this bit.
#define CONFIG_SW_HARD_STOP 0x0000 // Default; hard stop motor on switch.
#define CONFIG_SW_USER 0x0010 // Tie to the GoUntil and ReleaseSW
// commands to provide jog function.
// See page 25 of datasheet.
// Configure the motor voltage compensation mode (see page 34 of datasheet)
#define CONFIG_EN_VSCOMP 0x0020 // Mask for this bit.
#define CONFIG_VS_COMP_DISABLE 0x0000 // Disable motor voltage compensation.
#define CONFIG_VS_COMP_ENABLE 0x0020 // Enable motor voltage compensation.
// Configure overcurrent detection event handling
#define CONFIG_OC_SD 0x0080 // Mask for this bit.
#define CONFIG_OC_SD_DISABLE 0x0000 // Bridges do NOT shutdown on OC detect
#define CONFIG_OC_SD_ENABLE 0x0080 // Bridges shutdown on OC detect
// Configure the slew rate of the power bridge output
#define CONFIG_POW_SR 0x0300 // Mask for this bit field.
#define CONFIG_SR_180V_us 0x0000 // 180V/us
#define CONFIG_SR_290V_us 0x0200 // 290V/us
#define CONFIG_SR_530V_us 0x0300 // 530V/us
// Integer divisors for PWM sinewave generation
// See page 32 of the datasheet for more information on this.
#define CONFIG_F_PWM_DEC 0x1C00 // mask for this bit field
#define CONFIG_PWM_MUL_0_625 (0x00)<<10
#define CONFIG_PWM_MUL_0_75 (0x01)<<10
#define CONFIG_PWM_MUL_0_875 (0x02)<<10
#define CONFIG_PWM_MUL_1 (0x03)<<10
#define CONFIG_PWM_MUL_1_25 (0x04)<<10
#define CONFIG_PWM_MUL_1_5 (0x05)<<10
#define CONFIG_PWM_MUL_1_75 (0x06)<<10
#define CONFIG_PWM_MUL_2 (0x07)<<10
// Multiplier for the PWM sinewave frequency
#define CONFIG_F_PWM_INT 0xE000 // mask for this bit field.
#define CONFIG_PWM_DIV_1 (0x00)<<13
#define CONFIG_PWM_DIV_2 (0x01)<<13
#define CONFIG_PWM_DIV_3 (0x02)<<13
#define CONFIG_PWM_DIV_4 (0x03)<<13
#define CONFIG_PWM_DIV_5 (0x04)<<13
#define CONFIG_PWM_DIV_6 (0x05)<<13
#define CONFIG_PWM_DIV_7 (0x06)<<13
// Status register bit renames- read-only bits conferring information about the
// device to the user.
#define STATUS_HIZ 0x0001 // high when bridges are in HiZ mode
#define STATUS_BUSY 0x0002 // mirrors BUSY pin
#define STATUS_SW_F 0x0004 // low when switch open, high when closed
#define STATUS_SW_EVN 0x0008 // active high, set on switch falling edge,
// cleared by reading STATUS
#define STATUS_DIR 0x0010 // Indicates current motor direction.
// High is FWD, Low is REV.
#define STATUS_NOTPERF_CMD 0x0080 // Last command not performed.
#define STATUS_WRONG_CMD 0x0100 // Last command not valid.
#define STATUS_UVLO 0x0200 // Undervoltage lockout is active
#define STATUS_TH_WRN 0x0400 // Thermal warning
#define STATUS_TH_SD 0x0800 // Thermal shutdown
#define STATUS_OCD 0x1000 // Overcurrent detected
#define STATUS_STEP_LOSS_A 0x2000 // Stall detected on A bridge
#define STATUS_STEP_LOSS_B 0x4000 // Stall detected on B bridge
#define STATUS_SCK_MOD 0x8000 // Step clock mode is active
// Status register motor status field
#define STATUS_MOT_STATUS 0x0060 // field mask
#define STATUS_MOT_STATUS_STOPPED (0x0000)<<13 // Motor stopped
#define STATUS_MOT_STATUS_ACCELERATION (0x0001)<<13 // Motor accelerating
#define STATUS_MOT_STATUS_DECELERATION (0x0002)<<13 // Motor decelerating
#define STATUS_MOT_STATUS_CONST_SPD (0x0003)<<13 // Motor at constant speed
// Register address redefines.
// See the Param_Handler() function for more info about these.
#define ABS_POS 0x01
#define EL_POS 0x02
#define MARK 0x03
#define SPEED 0x04
#define ACC 0x05
#define DEC 0x06
#define MAX_SPEED 0x07
#define MIN_SPEED 0x08
#define FS_SPD 0x15
#define KVAL_HOLD 0x09
#define KVAL_RUN 0x0A
#define KVAL_ACC 0x0B
#define KVAL_DEC 0x0C
#define INT_SPD 0x0D
#define ST_SLP 0x0E
#define FN_SLP_ACC 0x0F
#define FN_SLP_DEC 0x10
#define K_THERM 0x11
#define ADC_OUT 0x12
#define OCD_TH 0x13
#define STALL_TH 0x14
#define STEP_MODE 0x16
#define ALARM_EN 0x17
#define CONFIG 0x18
#define STATUS 0x19
//dSPIN commands
#define NOP 0x00
#define SET_PARAM 0x00
#define GET_PARAM 0x20
#define RUN 0x50
#define STEP_CLOCK 0x58
#define MOVE 0x40
#define GOTO 0x60
#define GOTO_DIR 0x68
#define GO_UNTIL 0x82
#define RELEASE_SW 0x92
#define GO_HOME 0x70
#define GO_MARK 0x78
#define RESET_POS 0xD8
#define RESET_DEVICE 0xC0
#define SOFT_STOP 0xB0
#define HARD_STOP 0xB8
#define SOFT_HIZ 0xA0
#define HARD_HIZ 0xA8
#define GET_STATUS 0xD0
/* dSPIN direction options */
#define FWD 0x01
#define REV 0x00
/* dSPIN action options */
#define ACTION_RESET 0x00
#define ACTION_COPY 0x01
class L6470{
public:
L6470(int SSPin);
void init(int k_value);
void setMicroSteps(int microSteps);
void setCurrent(int current);
void setMaxSpeed(int speed);
void setMinSpeed(int speed);
void setAcc(float acceleration);
void setDec(float deceleration);
void setOverCurrent(unsigned int ma_current);
void setThresholdSpeed(float threshold);
void setStallCurrent(float ma_current);
unsigned long ParamHandler(byte param, unsigned long value);
void SetLowSpeedOpt(boolean enable);
void run(byte dir, float spd);
void Step_Clock(byte dir);
void goHome();
void setAsHome();
void goMark();
void move(long n_step);
void goTo(long pos);
void goTo_DIR(byte dir, long pos);
void goUntil(byte act, byte dir, unsigned long spd);
boolean isBusy();
void releaseSW(byte act, byte dir);
float getSpeed();
long getPos();
void setMark();
void setMark(long value);
void resetPos();
void resetDev();
void softStop();
void hardStop();
void softFree();
void free();
int getStatus();
void SetParam(byte param, unsigned long value);
private:
long convert(unsigned long val);
unsigned long GetParam(byte param);
unsigned long AccCalc(float stepsPerSecPerSec);
unsigned long DecCalc(float stepsPerSecPerSec);
unsigned long MaxSpdCalc(float stepsPerSec);
unsigned long MinSpdCalc(float stepsPerSec);
unsigned long FSCalc(float stepsPerSec);
unsigned long IntSpdCalc(float stepsPerSec);
unsigned long SpdCalc(float stepsPerSec);
unsigned long Param(unsigned long value, byte bit_len);
byte Xfer(byte data);
int _SSPin;
};
#endif

View file

@ -0,0 +1,53 @@
#######################################################
# keywords.txt - keywords file for the L6470 library
#
# ORIGINAL CODE 12/12/2011- Mike Hord, SparkFun Electronics
# Library by Adam Meyer of bildr Aug 18th 2012
#
# Released as MIT license
#######################################################
#######################################
# Datatypes (KEYWORD1)
#######################################
L6470 KEYWORD1
#######################################
# Methods and Functions (KEYWORD2)
#######################################
L6470 KEYWORD2
init KEYWORD2
setMicroSteps KEYWORD2
setCurrent KEYWORD2
setMaxSpeed KEYWORD2
setMinSpeed KEYWORD2
setAcc KEYWORD2
setDec KEYWORD2
setOverCurrent KEYWORD2
setThresholdSpeed KEYWORD2
setStallCurrent KEYWORD2
ParamHandler KEYWORD2
SetLowSpeedOpt KEYWORD2
run KEYWORD2
Step_Clock KEYWORD2
goHome KEYWORD2
goMark KEYWORD2
move KEYWORD2
goTo KEYWORD2
goTo_DIR KEYWORD2
goUntil KEYWORD2
isBusy KEYWORD2
releaseSW KEYWORD2
resetPos KEYWORD2
resetDev KEYWORD2
softStop KEYWORD2
hardStop KEYWORD2
softHiZ KEYWORD2
hardHiZ KEYWORD2
getStatus KEYWORD2
#######################################
# Constants (LITERAL1)
#######################################

View file

@ -0,0 +1,17 @@
#mac stuff
.DS_Store
#eclipse stuff
.classpath
.project
#processing stuff
generated/
examples/TMC26XMotorTester/processing/TMC26XMotorTest/application.*/
examples/TMC26XMotorTester/processing/TMC26XMotorTest/application.*
#eagle stuff
schematics/*.b#?
schematics/*.s#?
*.zip

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,10 @@
Copyright (c) 2012 Interactive Matter
based on the stepper library by Tom Igoe, et. al.
Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.

View file

@ -0,0 +1,71 @@
Arduino TMC26X Stepper Motor Controller Library
===============================================
License
-------
TMC26XStepper.cpp - - TMC 260/261/262 Stepper library for Wiring/Arduino
based on the stepper library by Tom Igoe, et. al.
Copyright (c) 2011, Interactive Matter, Marcus Nowotny
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
About
-----
The TMC26X is a stepper motor controller for bipolar stepper motors. From the trinamic web site:
The TMC262 is the first energy efficient high current high precision microstepping driver
IC for bipolar stepper motors. The unique high resolution sensorless load detection stallGuard2™
is used to for the worlds first integrated load dependent current control feature called coolStep™.
The ability to read out the load and detect an overload makes the TMC262 an optimum choice for
drives where a high reliability is desired at a low cost. The new patented spreadCycle PWM mixed
decay chopper scheme ensures best zero crossing performance as well as high speed operation.
The TMC262 can be driven with Step & Direction signals as well as by serial SPI™ interface.
Using the microPlyer allows to operate the motor with highest 256 μStep smoothness reducing the
input frequency to 16 μSteps. A full set of protection and diagnostic features makes this device
very rugged. It directly drives external MOSFETs for currents of up to 6A. This way it reaches
highest energy efficiency and allows driving of a high motor current without cooling measures
even at high environment temperatures.
The unique features of the TMC26X are that everything can (and must) be controlled in software:
* the motor current
* microstepping
* stall protection
* current reduction according to load
* stallGuard2™ sensorless load detection
* coolStep™ load dependent current control
* spreadCycle hysteresis PWM chopper
* microPlyer 16-to-256 μStep multiplier
* full protection and diagnostics
This makes the TMC26X a bit harder to use than other stepper motors but much more versatile.
This library resolves all the complicated stuff so that you can use TMC26X straight away.
Furthermore, all the settings are implemented in high level interfaces so that configuring your
motor is a breeze.
How to use
----------
Check out the Setup Guide here:
And the How To here:

View file

@ -0,0 +1,999 @@
/*
TMC26XStepper.cpp - - TMC26X Stepper library for Wiring/Arduino
based on the stepper library by Tom Igoe, et. al.
Copyright (c) 2011, Interactive Matter, Marcus Nowotny
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
#if defined(ARDUINO) && ARDUINO >= 100
#include <Arduino.h>
#else
#include <WProgram.h>
#endif
#include <SPI.h>
#include "TMC26XStepper.h"
//some default values used in initialization
#define DEFAULT_MICROSTEPPING_VALUE 32
//TMC26X register definitions
#define DRIVER_CONTROL_REGISTER 0x0ul
#define CHOPPER_CONFIG_REGISTER 0x80000ul
#define COOL_STEP_REGISTER 0xA0000ul
#define STALL_GUARD2_LOAD_MEASURE_REGISTER 0xC0000ul
#define DRIVER_CONFIG_REGISTER 0xE0000ul
#define REGISTER_BIT_PATTERN 0xFFFFFul
//definitions for the driver control register
#define MICROSTEPPING_PATTERN 0xFul
#define STEP_INTERPOLATION 0x200ul
#define DOUBLE_EDGE_STEP 0x100ul
#define VSENSE 0x40ul
#define READ_MICROSTEP_POSTION 0x0ul
#define READ_STALL_GUARD_READING 0x10ul
#define READ_STALL_GUARD_AND_COOL_STEP 0x20ul
#define READ_SELECTION_PATTERN 0x30ul
//definitions for the chopper config register
#define CHOPPER_MODE_STANDARD 0x0ul
#define CHOPPER_MODE_T_OFF_FAST_DECAY 0x4000ul
#define T_OFF_PATTERN 0xful
#define RANDOM_TOFF_TIME 0x2000ul
#define BLANK_TIMING_PATTERN 0x18000ul
#define BLANK_TIMING_SHIFT 15
#define HYSTERESIS_DECREMENT_PATTERN 0x1800ul
#define HYSTERESIS_DECREMENT_SHIFT 11
#define HYSTERESIS_LOW_VALUE_PATTERN 0x780ul
#define HYSTERESIS_LOW_SHIFT 7
#define HYSTERESIS_START_VALUE_PATTERN 0x78ul
#define HYSTERESIS_START_VALUE_SHIFT 4
#define T_OFF_TIMING_PATERN 0xFul
//definitions for cool step register
#define MINIMUM_CURRENT_FOURTH 0x8000ul
#define CURRENT_DOWN_STEP_SPEED_PATTERN 0x6000ul
#define SE_MAX_PATTERN 0xF00ul
#define SE_CURRENT_STEP_WIDTH_PATTERN 0x60ul
#define SE_MIN_PATTERN 0xful
//definitions for stall guard2 current register
#define STALL_GUARD_FILTER_ENABLED 0x10000ul
#define STALL_GUARD_TRESHHOLD_VALUE_PATTERN 0x17F00ul
#define CURRENT_SCALING_PATTERN 0x1Ful
#define STALL_GUARD_CONFIG_PATTERN 0x17F00ul
#define STALL_GUARD_VALUE_PATTERN 0x7F00ul
//definitions for the input from the TCM260
#define STATUS_STALL_GUARD_STATUS 0x1ul
#define STATUS_OVER_TEMPERATURE_SHUTDOWN 0x2ul
#define STATUS_OVER_TEMPERATURE_WARNING 0x4ul
#define STATUS_SHORT_TO_GROUND_A 0x8ul
#define STATUS_SHORT_TO_GROUND_B 0x10ul
#define STATUS_OPEN_LOAD_A 0x20ul
#define STATUS_OPEN_LOAD_B 0x40ul
#define STATUS_STAND_STILL 0x80ul
#define READOUT_VALUE_PATTERN 0xFFC00ul
//default values
#define INITIAL_MICROSTEPPING 0x3ul //32th microstepping
//debuging output
//#define DEBUG
/*
* Constructor
* number_of_steps - the steps per rotation
* cs_pin - the SPI client select pin
* dir_pin - the pin where the direction pin is connected
* step_pin - the pin where the step pin is connected
*/
TMC26XStepper::TMC26XStepper(int number_of_steps, int cs_pin, int dir_pin, int step_pin, unsigned int current, unsigned int resistor)
{
//we are not started yet
started=false;
//by default cool step is not enabled
cool_step_enabled=false;
//save the pins for later use
this->cs_pin=cs_pin;
this->dir_pin=dir_pin;
this->step_pin = step_pin;
//store the current sense resistor value for later use
this->resistor = resistor;
//initizalize our status values
this->steps_left = 0;
this->direction = 0;
//initialize register values
driver_control_register_value=DRIVER_CONTROL_REGISTER | INITIAL_MICROSTEPPING;
chopper_config_register=CHOPPER_CONFIG_REGISTER;
//setting the default register values
driver_control_register_value=DRIVER_CONTROL_REGISTER|INITIAL_MICROSTEPPING;
microsteps = (1 << INITIAL_MICROSTEPPING);
chopper_config_register=CHOPPER_CONFIG_REGISTER;
cool_step_register_value=COOL_STEP_REGISTER;
stall_guard2_current_register_value=STALL_GUARD2_LOAD_MEASURE_REGISTER;
driver_configuration_register_value = DRIVER_CONFIG_REGISTER | READ_STALL_GUARD_READING;
//set the current
setCurrent(current);
//set to a conservative start value
setConstantOffTimeChopper(7, 54, 13,12,1);
//set a nice microstepping value
setMicrosteps(DEFAULT_MICROSTEPPING_VALUE);
//save the number of steps
this->number_of_steps = number_of_steps;
}
/*
* start & configure the stepper driver
* just must be called.
*/
void TMC26XStepper::start() {
#ifdef DEBUG
Serial.println("TMC26X stepper library");
Serial.print("CS pin: ");
Serial.println(cs_pin);
Serial.print("DIR pin: ");
Serial.println(dir_pin);
Serial.print("STEP pin: ");
Serial.println(step_pin);
Serial.print("current scaling: ");
Serial.println(current_scaling,DEC);
#endif
//set the pins as output & its initial value
pinMode(step_pin, OUTPUT);
pinMode(dir_pin, OUTPUT);
pinMode(cs_pin, OUTPUT);
digitalWrite(step_pin, LOW);
digitalWrite(dir_pin, LOW);
digitalWrite(cs_pin, HIGH);
//configure the SPI interface
SPI.setBitOrder(MSBFIRST);
SPI.setClockDivider(SPI_CLOCK_DIV8);
//todo this does not work reliably - find a way to foolprof set it (e.g. while communicating
//SPI.setDataMode(SPI_MODE3);
SPI.begin();
//set the initial values
send262(driver_control_register_value);
send262(chopper_config_register);
send262(cool_step_register_value);
send262(stall_guard2_current_register_value);
send262(driver_configuration_register_value);
//save that we are in running mode
started=true;
}
/*
Mark the driver as unstarted to be able to start it again
*/
void TMC26XStepper::un_start() {
started=false;
}
/*
Sets the speed in revs per minute
*/
void TMC26XStepper::setSpeed(unsigned int whatSpeed)
{
this->speed = whatSpeed;
this->step_delay = (60UL * 1000UL * 1000UL) / ((unsigned long)this->number_of_steps * (unsigned long)whatSpeed * (unsigned long)this->microsteps);
#ifdef DEBUG
Serial.print("Step delay in micros: ");
Serial.println(this->step_delay);
#endif
//update the next step time
this->next_step_time = this->last_step_time+this->step_delay;
}
unsigned int TMC26XStepper::getSpeed(void) {
return this->speed;
}
/*
Moves the motor steps_to_move steps. If the number is negative,
the motor moves in the reverse direction.
*/
char TMC26XStepper::step(int steps_to_move)
{
if (this->steps_left==0) {
this->steps_left = abs(steps_to_move); // how many steps to take
// determine direction based on whether steps_to_mode is + or -:
if (steps_to_move > 0) {
this->direction = 1;
} else if (steps_to_move < 0) {
this->direction = 0;
}
return 0;
} else {
return -1;
}
}
char TMC26XStepper::move(void) {
// decrement the number of steps, moving one step each time:
if(this->steps_left>0) {
unsigned long time = micros();
// move only if the appropriate delay has passed:
if (time >= this->next_step_time) {
// increment or decrement the step number,
// depending on direction:
if (this->direction == 1) {
digitalWrite(step_pin, HIGH);
} else {
digitalWrite(dir_pin, HIGH);
digitalWrite(step_pin, HIGH);
}
// get the timeStamp of when you stepped:
this->last_step_time = time;
this->next_step_time = time+this->step_delay;
// decrement the steps left:
steps_left--;
//disable the step & dir pins
digitalWrite(step_pin, LOW);
digitalWrite(dir_pin, LOW);
}
return -1;
}
return 0;
}
char TMC26XStepper::isMoving(void) {
return (this->steps_left>0);
}
unsigned int TMC26XStepper::getStepsLeft(void) {
return this->steps_left;
}
char TMC26XStepper::stop(void) {
//note to self if the motor is currently moving
char state = isMoving();
//stop the motor
this->steps_left = 0;
this->direction = 0;
//return if it was moving
return state;
}
void TMC26XStepper::setCurrent(unsigned int current) {
unsigned char current_scaling = 0;
//calculate the current scaling from the max current setting (in mA)
double mASetting = (double)current;
double resistor_value = (double) this->resistor;
// remove vesense flag
this->driver_configuration_register_value &= ~(VSENSE);
//this is derrived from I=(cs+1)/32*(Vsense/Rsense)
//leading to cs = CS = 32*R*I/V (with V = 0,31V oder 0,165V and I = 1000*current)
//with Rsense=0,15
//for vsense = 0,310V (VSENSE not set)
//or vsense = 0,165V (VSENSE set)
current_scaling = (byte)((resistor_value*mASetting*32.0/(0.31*1000.0*1000.0))-0.5); //theoretically - 1.0 for better rounding it is 0.5
//check if the current scalingis too low
if (current_scaling<16) {
//set the csense bit to get a use half the sense voltage (to support lower motor currents)
this->driver_configuration_register_value |= VSENSE;
//and recalculate the current setting
current_scaling = (byte)((resistor_value*mASetting*32.0/(0.165*1000.0*1000.0))-0.5); //theoretically - 1.0 for better rounding it is 0.5
#ifdef DEBUG
Serial.print("CS (Vsense=1): ");
Serial.println(current_scaling);
} else {
Serial.print("CS: ");
Serial.println(current_scaling);
#endif
}
//do some sanity checks
if (current_scaling>31) {
current_scaling=31;
}
//delete the old value
stall_guard2_current_register_value &= ~(CURRENT_SCALING_PATTERN);
//set the new current scaling
stall_guard2_current_register_value |= current_scaling;
//if started we directly send it to the motor
if (started) {
send262(driver_configuration_register_value);
send262(stall_guard2_current_register_value);
}
}
unsigned int TMC26XStepper::getCurrent(void) {
//we calculate the current according to the datasheet to be on the safe side
//this is not the fastest but the most accurate and illustrative way
double result = (double)(stall_guard2_current_register_value & CURRENT_SCALING_PATTERN);
double resistor_value = (double)this->resistor;
double voltage = (driver_configuration_register_value & VSENSE)? 0.165:0.31;
result = (result+1.0)/32.0*voltage/resistor_value*1000.0*1000.0;
return (unsigned int)result;
}
void TMC26XStepper::setStallGuardThreshold(char stall_guard_threshold, char stall_guard_filter_enabled) {
if (stall_guard_threshold<-64) {
stall_guard_threshold = -64;
//We just have 5 bits
} else if (stall_guard_threshold > 63) {
stall_guard_threshold = 63;
}
//add trim down to 7 bits
stall_guard_threshold &=0x7f;
//delete old stall guard settings
stall_guard2_current_register_value &= ~(STALL_GUARD_CONFIG_PATTERN);
if (stall_guard_filter_enabled) {
stall_guard2_current_register_value |= STALL_GUARD_FILTER_ENABLED;
}
//Set the new stall guard threshold
stall_guard2_current_register_value |= (((unsigned long)stall_guard_threshold << 8) & STALL_GUARD_CONFIG_PATTERN);
//if started we directly send it to the motor
if (started) {
send262(stall_guard2_current_register_value);
}
}
char TMC26XStepper::getStallGuardThreshold(void) {
unsigned long stall_guard_threshold = stall_guard2_current_register_value & STALL_GUARD_VALUE_PATTERN;
//shift it down to bit 0
stall_guard_threshold >>=8;
//convert the value to an int to correctly handle the negative numbers
char result = stall_guard_threshold;
//check if it is negative and fill it up with leading 1 for proper negative number representation
if (result & _BV(6)) {
result |= 0xC0;
}
return result;
}
char TMC26XStepper::getStallGuardFilter(void) {
if (stall_guard2_current_register_value & STALL_GUARD_FILTER_ENABLED) {
return -1;
} else {
return 0;
}
}
/*
* Set the number of microsteps per step.
* 0,2,4,8,16,32,64,128,256 is supported
* any value in between will be mapped to the next smaller value
* 0 and 1 set the motor in full step mode
*/
void TMC26XStepper::setMicrosteps(int number_of_steps) {
long setting_pattern;
//poor mans log
if (number_of_steps>=256) {
setting_pattern=0;
microsteps=256;
} else if (number_of_steps>=128) {
setting_pattern=1;
microsteps=128;
} else if (number_of_steps>=64) {
setting_pattern=2;
microsteps=64;
} else if (number_of_steps>=32) {
setting_pattern=3;
microsteps=32;
} else if (number_of_steps>=16) {
setting_pattern=4;
microsteps=16;
} else if (number_of_steps>=8) {
setting_pattern=5;
microsteps=8;
} else if (number_of_steps>=4) {
setting_pattern=6;
microsteps=4;
} else if (number_of_steps>=2) {
setting_pattern=7;
microsteps=2;
//1 and 0 lead to full step
} else if (number_of_steps<=1) {
setting_pattern=8;
microsteps=1;
}
#ifdef DEBUG
Serial.print("Microstepping: ");
Serial.println(microsteps);
#endif
//delete the old value
this->driver_control_register_value &=0xFFFF0ul;
//set the new value
this->driver_control_register_value |=setting_pattern;
//if started we directly send it to the motor
if (started) {
send262(driver_control_register_value);
}
//recalculate the stepping delay by simply setting the speed again
this->setSpeed(this->speed);
}
/*
* returns the effective number of microsteps at the moment
*/
int TMC26XStepper::getMicrosteps(void) {
return microsteps;
}
/*
* constant_off_time: The off time setting controls the minimum chopper frequency.
* For most applications an off time within the range of 5μs to 20μs will fit.
* 2...15: off time setting
*
* blank_time: Selects the comparator blank time. This time needs to safely cover the switching event and the
* duration of the ringing on the sense resistor. For
* 0: min. setting 3: max. setting
*
* fast_decay_time_setting: Fast decay time setting. With CHM=1, these bits control the portion of fast decay for each chopper cycle.
* 0: slow decay only
* 1...15: duration of fast decay phase
*
* sine_wave_offset: Sine wave offset. With CHM=1, these bits control the sine wave offset.
* A positive offset corrects for zero crossing error.
* -3..-1: negative offset 0: no offset 1...12: positive offset
*
* use_current_comparator: Selects usage of the current comparator for termination of the fast decay cycle.
* If current comparator is enabled, it terminates the fast decay cycle in case the current
* reaches a higher negative value than the actual positive value.
* 1: enable comparator termination of fast decay cycle
* 0: end by time only
*/
void TMC26XStepper::setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, unsigned char use_current_comparator) {
//perform some sanity checks
if (constant_off_time<2) {
constant_off_time=2;
} else if (constant_off_time>15) {
constant_off_time=15;
}
//save the constant off time
this->constant_off_time = constant_off_time;
char blank_value;
//calculate the value acc to the clock cycles
if (blank_time>=54) {
blank_value=3;
} else if (blank_time>=36) {
blank_value=2;
} else if (blank_time>=24) {
blank_value=1;
} else {
blank_value=0;
}
if (fast_decay_time_setting<0) {
fast_decay_time_setting=0;
} else if (fast_decay_time_setting>15) {
fast_decay_time_setting=15;
}
if (sine_wave_offset < -3) {
sine_wave_offset = -3;
} else if (sine_wave_offset>12) {
sine_wave_offset = 12;
}
//shift the sine_wave_offset
sine_wave_offset +=3;
//calculate the register setting
//first of all delete all the values for this
chopper_config_register &= ~((1<<12) | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN);
//set the constant off pattern
chopper_config_register |= CHOPPER_MODE_T_OFF_FAST_DECAY;
//set the blank timing value
chopper_config_register |= ((unsigned long)blank_value) << BLANK_TIMING_SHIFT;
//setting the constant off time
chopper_config_register |= constant_off_time;
//set the fast decay time
//set msb
chopper_config_register |= (((unsigned long)(fast_decay_time_setting & 0x8))<<HYSTERESIS_DECREMENT_SHIFT);
//other bits
chopper_config_register |= (((unsigned long)(fast_decay_time_setting & 0x7))<<HYSTERESIS_START_VALUE_SHIFT);
//set the sine wave offset
chopper_config_register |= (unsigned long)sine_wave_offset << HYSTERESIS_LOW_SHIFT;
//using the current comparator?
if (!use_current_comparator) {
chopper_config_register |= (1<<12);
}
//if started we directly send it to the motor
if (started) {
send262(driver_control_register_value);
}
}
/*
* constant_off_time: The off time setting controls the minimum chopper frequency.
* For most applications an off time within the range of 5μs to 20μs will fit.
* 2...15: off time setting
*
* blank_time: Selects the comparator blank time. This time needs to safely cover the switching event and the
* duration of the ringing on the sense resistor. For
* 0: min. setting 3: max. setting
*
* hysteresis_start: Hysteresis start setting. Please remark, that this value is an offset to the hysteresis end value HEND.
* 1...8
*
* hysteresis_end: Hysteresis end setting. Sets the hysteresis end value after a number of decrements. Decrement interval time is controlled by HDEC.
* The sum HSTRT+HEND must be <16. At a current setting CS of max. 30 (amplitude reduced to 240), the sum is not limited.
* -3..-1: negative HEND 0: zero HEND 1...12: positive HEND
*
* hysteresis_decrement: Hysteresis decrement setting. This setting determines the slope of the hysteresis during on time and during fast decay time.
* 0: fast decrement 3: very slow decrement
*/
void TMC26XStepper::setSpreadCycleChopper(char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement) {
//perform some sanity checks
if (constant_off_time<2) {
constant_off_time=2;
} else if (constant_off_time>15) {
constant_off_time=15;
}
//save the constant off time
this->constant_off_time = constant_off_time;
char blank_value;
//calculate the value acc to the clock cycles
if (blank_time>=54) {
blank_value=3;
} else if (blank_time>=36) {
blank_value=2;
} else if (blank_time>=24) {
blank_value=1;
} else {
blank_value=0;
}
if (hysteresis_start<1) {
hysteresis_start=1;
} else if (hysteresis_start>8) {
hysteresis_start=8;
}
hysteresis_start--;
if (hysteresis_end < -3) {
hysteresis_end = -3;
} else if (hysteresis_end>12) {
hysteresis_end = 12;
}
//shift the hysteresis_end
hysteresis_end +=3;
if (hysteresis_decrement<0) {
hysteresis_decrement=0;
} else if (hysteresis_decrement>3) {
hysteresis_decrement=3;
}
//first of all delete all the values for this
chopper_config_register &= ~(CHOPPER_MODE_T_OFF_FAST_DECAY | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN);
//set the blank timing value
chopper_config_register |= ((unsigned long)blank_value) << BLANK_TIMING_SHIFT;
//setting the constant off time
chopper_config_register |= constant_off_time;
//set the hysteresis_start
chopper_config_register |= ((unsigned long)hysteresis_start) << HYSTERESIS_START_VALUE_SHIFT;
//set the hysteresis end
chopper_config_register |= ((unsigned long)hysteresis_end) << HYSTERESIS_LOW_SHIFT;
//set the hystereis decrement
chopper_config_register |= ((unsigned long)blank_value) << BLANK_TIMING_SHIFT;
//if started we directly send it to the motor
if (started) {
send262(driver_control_register_value);
}
}
/*
* In a constant off time chopper scheme both coil choppers run freely, i.e. are not synchronized.
* The frequency of each chopper mainly depends on the coil current and the position dependant motor coil inductivity, thus it depends on the microstep position.
* With some motors a slightly audible beat can occur between the chopper frequencies, especially when they are near to each other. This typically occurs at a
* few microstep positions within each quarter wave. This effect normally is not audible when compared to mechanical noise generated by ball bearings, etc.
* Further factors which can cause a similar effect are a poor layout of sense resistor GND connection.
* Hint: A common factor, which can cause motor noise, is a bad PCB layout causing coupling of both sense resistor voltages
* (please refer to sense resistor layout hint in chapter 8.1).
* In order to minimize the effect of a beat between both chopper frequencies, an internal random generator is provided.
* It modulates the slow decay time setting when switched on by the RNDTF bit. The RNDTF feature further spreads the chopper spectrum,
* reducing electromagnetic emission on single frequencies.
*/
void TMC26XStepper::setRandomOffTime(char value) {
if (value) {
chopper_config_register |= RANDOM_TOFF_TIME;
} else {
chopper_config_register &= ~(RANDOM_TOFF_TIME);
}
//if started we directly send it to the motor
if (started) {
send262(driver_control_register_value);
}
}
void TMC26XStepper::setCoolStepConfiguration(unsigned int lower_SG_threshold, unsigned int SG_hysteresis, unsigned char current_decrement_step_size,
unsigned char current_increment_step_size, unsigned char lower_current_limit) {
//sanitize the input values
if (lower_SG_threshold>480) {
lower_SG_threshold = 480;
}
//divide by 32
lower_SG_threshold >>=5;
if (SG_hysteresis>480) {
SG_hysteresis=480;
}
//divide by 32
SG_hysteresis >>=5;
if (current_decrement_step_size>3) {
current_decrement_step_size=3;
}
if (current_increment_step_size>3) {
current_increment_step_size=3;
}
if (lower_current_limit>1) {
lower_current_limit=1;
}
//store the lower level in order to enable/disable the cool step
this->cool_step_lower_threshold=lower_SG_threshold;
//if cool step is not enabled we delete the lower value to keep it disabled
if (!this->cool_step_enabled) {
lower_SG_threshold=0;
}
//the good news is that we can start with a complete new cool step register value
//and simply set the values in the register
cool_step_register_value = ((unsigned long)lower_SG_threshold) | (((unsigned long)SG_hysteresis)<<8) | (((unsigned long)current_decrement_step_size)<<5)
| (((unsigned long)current_increment_step_size)<<13) | (((unsigned long)lower_current_limit)<<15)
//and of course we have to include the signature of the register
| COOL_STEP_REGISTER;
//Serial.println(cool_step_register_value,HEX);
if (started) {
send262(cool_step_register_value);
}
}
void TMC26XStepper::setCoolStepEnabled(boolean enabled) {
//simply delete the lower limit to disable the cool step
cool_step_register_value &= ~SE_MIN_PATTERN;
//and set it to the proper value if cool step is to be enabled
if (enabled) {
cool_step_register_value |=this->cool_step_lower_threshold;
}
//and save the enabled status
this->cool_step_enabled = enabled;
//save the register value
if (started) {
send262(cool_step_register_value);
}
}
boolean TMC26XStepper::isCoolStepEnabled(void) {
return this->cool_step_enabled;
}
unsigned int TMC26XStepper::getCoolStepLowerSgThreshold() {
//we return our internally stored value - in order to provide the correct setting even if cool step is not enabled
return this->cool_step_lower_threshold<<5;
}
unsigned int TMC26XStepper::getCoolStepUpperSgThreshold() {
return (unsigned char)((cool_step_register_value & SE_MAX_PATTERN)>>8)<<5;
}
unsigned char TMC26XStepper::getCoolStepCurrentIncrementSize() {
return (unsigned char)((cool_step_register_value & CURRENT_DOWN_STEP_SPEED_PATTERN)>>13);
}
unsigned char TMC26XStepper::getCoolStepNumberOfSGReadings() {
return (unsigned char)((cool_step_register_value & SE_CURRENT_STEP_WIDTH_PATTERN)>>5);
}
unsigned char TMC26XStepper::getCoolStepLowerCurrentLimit() {
return (unsigned char)((cool_step_register_value & MINIMUM_CURRENT_FOURTH)>>15);
}
void TMC26XStepper::setEnabled(boolean enabled) {
//delete the t_off in the chopper config to get sure
chopper_config_register &= ~(T_OFF_PATTERN);
if (enabled) {
//and set the t_off time
chopper_config_register |= this->constant_off_time;
}
//if not enabled we don't have to do anything since we already delete t_off from the register
if (started) {
send262(chopper_config_register);
}
}
boolean TMC26XStepper::isEnabled() {
if (chopper_config_register & T_OFF_PATTERN) {
return true;
} else {
return false;
}
}
/*
* reads a value from the TMC26X status register. The value is not obtained directly but can then
* be read by the various status routines.
*
*/
void TMC26XStepper::readStatus(char read_value) {
unsigned long old_driver_configuration_register_value = driver_configuration_register_value;
//reset the readout configuration
driver_configuration_register_value &= ~(READ_SELECTION_PATTERN);
//this now equals TMC26X_READOUT_POSITION - so we just have to check the other two options
if (read_value == TMC26X_READOUT_STALLGUARD) {
driver_configuration_register_value |= READ_STALL_GUARD_READING;
} else if (read_value == TMC26X_READOUT_CURRENT) {
driver_configuration_register_value |= READ_STALL_GUARD_AND_COOL_STEP;
}
//all other cases are ignored to prevent funny values
//check if the readout is configured for the value we are interested in
if (driver_configuration_register_value!=old_driver_configuration_register_value) {
//because then we need to write the value twice - one time for configuring, second time to get the value, see below
send262(driver_configuration_register_value);
}
//write the configuration to get the last status
send262(driver_configuration_register_value);
}
int TMC26XStepper::getMotorPosition(void) {
//we read it out even if we are not started yet - perhaps it is useful information for somebody
readStatus(TMC26X_READOUT_POSITION);
return getReadoutValue();
}
//reads the stall guard setting from last status
//returns -1 if stallguard information is not present
int TMC26XStepper::getCurrentStallGuardReading(void) {
//if we don't yet started there cannot be a stall guard value
if (!started) {
return -1;
}
//not time optimal, but solution optiomal:
//first read out the stall guard value
readStatus(TMC26X_READOUT_STALLGUARD);
return getReadoutValue();
}
unsigned char TMC26XStepper::getCurrentCSReading(void) {
//if we don't yet started there cannot be a stall guard value
if (!started) {
return 0;
}
//not time optimal, but solution optiomal:
//first read out the stall guard value
readStatus(TMC26X_READOUT_CURRENT);
return (getReadoutValue() & 0x1f);
}
unsigned int TMC26XStepper::getCurrentCurrent(void) {
double result = (double)getCurrentCSReading();
double resistor_value = (double)this->resistor;
double voltage = (driver_configuration_register_value & VSENSE)? 0.165:0.31;
result = (result+1.0)/32.0*voltage/resistor_value*1000.0*1000.0;
return (unsigned int)result;
}
/*
return true if the stallguard threshold has been reached
*/
boolean TMC26XStepper::isStallGuardOverThreshold(void) {
if (!this->started) {
return false;
}
return (driver_status_result & STATUS_STALL_GUARD_STATUS);
}
/*
returns if there is any over temperature condition:
OVER_TEMPERATURE_PREWARING if pre warning level has been reached
OVER_TEMPERATURE_SHUTDOWN if the temperature is so hot that the driver is shut down
Any of those levels are not too good.
*/
char TMC26XStepper::getOverTemperature(void) {
if (!this->started) {
return 0;
}
if (driver_status_result & STATUS_OVER_TEMPERATURE_SHUTDOWN) {
return TMC26X_OVERTEMPERATURE_SHUTDOWN;
}
if (driver_status_result & STATUS_OVER_TEMPERATURE_WARNING) {
return TMC26X_OVERTEMPERATURE_PREWARING;
}
return 0;
}
//is motor channel A shorted to ground
boolean TMC26XStepper::isShortToGroundA(void) {
if (!this->started) {
return false;
}
return (driver_status_result & STATUS_SHORT_TO_GROUND_A);
}
//is motor channel B shorted to ground
boolean TMC26XStepper::isShortToGroundB(void) {
if (!this->started) {
return false;
}
return (driver_status_result & STATUS_SHORT_TO_GROUND_B);
}
//is motor channel A connected
boolean TMC26XStepper::isOpenLoadA(void) {
if (!this->started) {
return false;
}
return (driver_status_result & STATUS_OPEN_LOAD_A);
}
//is motor channel B connected
boolean TMC26XStepper::isOpenLoadB(void) {
if (!this->started) {
return false;
}
return (driver_status_result & STATUS_OPEN_LOAD_B);
}
//is chopper inactive since 2^20 clock cycles - defaults to ~0,08s
boolean TMC26XStepper::isStandStill(void) {
if (!this->started) {
return false;
}
return (driver_status_result & STATUS_STAND_STILL);
}
//is chopper inactive since 2^20 clock cycles - defaults to ~0,08s
boolean TMC26XStepper::isStallGuardReached(void) {
if (!this->started) {
return false;
}
return (driver_status_result & STATUS_STALL_GUARD_STATUS);
}
//reads the stall guard setting from last status
//returns -1 if stallguard inforamtion is not present
int TMC26XStepper::getReadoutValue(void) {
return (int)(driver_status_result >> 10);
}
int TMC26XStepper::getResistor() {
return this->resistor;
}
boolean TMC26XStepper::isCurrentScalingHalfed() {
if (this->driver_configuration_register_value & VSENSE) {
return true;
} else {
return false;
}
}
/*
version() returns the version of the library:
*/
int TMC26XStepper::version(void)
{
return 1;
}
void TMC26XStepper::debugLastStatus() {
#ifdef DEBUG
if (this->started) {
if (this->getOverTemperature()&TMC26X_OVERTEMPERATURE_PREWARING) {
Serial.println("WARNING: Overtemperature Prewarning!");
} else if (this->getOverTemperature()&TMC26X_OVERTEMPERATURE_SHUTDOWN) {
Serial.println("ERROR: Overtemperature Shutdown!");
}
if (this->isShortToGroundA()) {
Serial.println("ERROR: SHORT to ground on channel A!");
}
if (this->isShortToGroundB()) {
Serial.println("ERROR: SHORT to ground on channel A!");
}
if (this->isOpenLoadA()) {
Serial.println("ERROR: Channel A seems to be unconnected!");
}
if (this->isOpenLoadB()) {
Serial.println("ERROR: Channel B seems to be unconnected!");
}
if (this->isStallGuardReached()) {
Serial.println("INFO: Stall Guard level reached!");
}
if (this->isStandStill()) {
Serial.println("INFO: Motor is standing still.");
}
unsigned long readout_config = driver_configuration_register_value & READ_SELECTION_PATTERN;
int value = getReadoutValue();
if (readout_config == READ_MICROSTEP_POSTION) {
Serial.print("Microstep postion phase A: ");
Serial.println(value);
} else if (readout_config == READ_STALL_GUARD_READING) {
Serial.print("Stall Guard value:");
Serial.println(value);
} else if (readout_config == READ_STALL_GUARD_AND_COOL_STEP) {
int stallGuard = value & 0xf;
int current = value & 0x1F0;
Serial.print("Approx Stall Guard: ");
Serial.println(stallGuard);
Serial.print("Current level");
Serial.println(current);
}
}
#endif
}
/*
* send register settings to the stepper driver via SPI
* returns the current status
*/
inline void TMC26XStepper::send262(unsigned long datagram) {
unsigned long i_datagram;
//preserver the previous spi mode
unsigned char oldMode = SPCR & SPI_MODE_MASK;
//if the mode is not correct set it to mode 3
if (oldMode != SPI_MODE3) {
SPI.setDataMode(SPI_MODE3);
}
//select the TMC driver
digitalWrite(cs_pin,LOW);
//ensure that only valid bist are set (0-19)
//datagram &=REGISTER_BIT_PATTERN;
#ifdef DEBUG
Serial.print("Sending ");
Serial.println(datagram,HEX);
#endif
//write/read the values
i_datagram = SPI.transfer((datagram >> 16) & 0xff);
i_datagram <<= 8;
i_datagram |= SPI.transfer((datagram >> 8) & 0xff);
i_datagram <<= 8;
i_datagram |= SPI.transfer((datagram) & 0xff);
i_datagram >>= 4;
#ifdef DEBUG
Serial.print("Received ");
Serial.println(i_datagram,HEX);
debugLastStatus();
#endif
//deselect the TMC chip
digitalWrite(cs_pin,HIGH);
//restore the previous SPI mode if neccessary
//if the mode is not correct set it to mode 3
if (oldMode != SPI_MODE3) {
SPI.setDataMode(oldMode);
}
//store the datagram as status result
driver_status_result = i_datagram;
}

View file

@ -0,0 +1,607 @@
/*
TMC26XStepper.cpp - - TMC26X Stepper library for Wiring/Arduino
based on the stepper library by Tom Igoe, et. al.
Copyright (c) 2011, Interactive Matter, Marcus Nowotny
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
// ensure this library description is only included once
#ifndef TMC26XStepper_h
#define TMC26XStepper_h
//! return value for TMC26XStepper.getOverTemperature() if there is a overtemperature situation in the TMC chip
/*!
* This warning indicates that the TCM chip is too warm.
* It is still working but some parameters may be inferior.
* You should do something against it.
*/
#define TMC26X_OVERTEMPERATURE_PREWARING 1
//! return value for TMC26XStepper.getOverTemperature() if there is a overtemperature shutdown in the TMC chip
/*!
* This warning indicates that the TCM chip is too warm to operate and has shut down to prevent damage.
* It will stop working until it cools down again.
* If you encouter this situation you must do something against it. Like reducing the current or improving the PCB layout
* and/or heat management.
*/
#define TMC26X_OVERTEMPERATURE_SHUTDOWN 2
//which values can be read out
/*!
* Selects to readout the microstep position from the motor.
*\sa readStatus()
*/
#define TMC26X_READOUT_POSITION 0
/*!
* Selects to read out the StallGuard value of the motor.
*\sa readStatus()
*/
#define TMC26X_READOUT_STALLGUARD 1
/*!
* Selects to read out the current current setting (acc. to CoolStep) and the upper bits of the StallGuard value from the motor.
*\sa readStatus(), setCurrent()
*/
#define TMC26X_READOUT_CURRENT 3
/*!
* Define to set the minimum current for CoolStep operation to 1/2 of the selected CS minium.
*\sa setCoolStepConfiguration()
*/
#define COOL_STEP_HALF_CS_LIMIT 0
/*!
* Define to set the minimum current for CoolStep operation to 1/4 of the selected CS minium.
*\sa setCoolStepConfiguration()
*/
#define COOL_STEP_QUARTDER_CS_LIMIT 1
/*!
* \class TMC26XStepper
* \brief Class representing a TMC26X stepper driver
*
* In order to use one fo those drivers in your Arduino code you have to create an object of that class:
* \code
* TMC26XStepper stepper = TMC26XStepper(200,1,2,3,500);
* \endcode
* see TMC26XStepper(int number_of_steps, int cs_pin, int dir_pin, int step_pin, unsigned int rms_current)
*
* Keep in mind that you need to start the driver with start() in order to get the TMC26X configured.
*
* The most important function is the move(). It checks if the motor has to do a step or not.
* It is important that you call move() as often as possible in your Arduino loop() routine. I suggest
* to use a very fast loop routine and always call it at the beginning or the end.
*
* In order to move you have to provide a movement speed with setSpeed(). The speed is a positive value setting
* the rotations per minute.
*
* To really move the motor you have to call step() to tell the driver to move the motor the given number
* of steps in the given direction. Positive values move the motor in one direction, negative values in the other direction.
*
* You can check with isMoving() if the mototr is still moving or stop it apruptely with stop().
*/
class TMC26XStepper {
public:
/*!
* \brief creates a new represenatation of a stepper motor connected to a TMC26X stepper driver
*
* This is the main constructor. If in doubt use this. You must provide all parameters as described below.
*
* \param number_of_steps the number of steps the motor has per rotation.
* \param cs_pin The Arduino pin you have connected the Cient Select Pin (!CS) of the TMC26X for SPI
* \param dir_pin the number of the Arduino pin the Direction input of the TMC26X is connected
* \param step_pin the number of the Arduino pin the step pin of the TMC26X driver is connected.
* \param rms_current the maximum current to privide to the motor in mA (!). A value of 200 would send up to 200mA to the motor
* \param resistor the current sense resistor in milli Ohm, defaults to ,15 Ohm ( or 150 milli Ohm) as in the TMC260 Arduino Shield
*
* Keep in mind that you must also call TMC26XStepper.start() in order to configure the stepper driver for use.
*
* By default the Constant Off Time chopper is used, see TCM262Stepper.setConstantOffTimeChopper() for details.
* This should work on most motors (YMMV). You may want to configure and use the Spread Cycle Chopper, see setSpreadCycleChopper().
*
* By default a microstepping of 1/32th is used to provide a smooth motor run, while still giving a good progression per step.
* You can select a different stepping with setMicrosteps() to aa different value.
* \sa start(), setMicrosteps()
*/
TMC26XStepper(int number_of_steps, int cs_pin, int dir_pin, int step_pin, unsigned int current, unsigned int resistor=150);
/*!
* \brief configures and starts the TMC26X stepper driver. Before you called this function the stepper driver is in nonfunctional mode.
*
* This routine configures the TMC26X stepper driver for the given values via SPI.
* Most member functions are non functional if the driver has not been started.
* Therefore it is best to call this in your Arduino setup() function.
*/
void start();
/*!
* \brief resets the stepper in unconfigured mode.
*
* This routine enables you to call start again. It does not change anything
* in the internal stepper configuration or the desired configuration.
* It just marks the stepper as not yet startet. You do not have to reconfigure
* the stepper to start it again, but it is not reset to any factory settings
* this has to be configured back by yourself.
* (Hint: Normally you do not need this function)
*/
void un_start();
/*!
* \brief Sets the rotation speed in revolutions per minute.
* \param whatSpeed the desired speed in rotations per minute.
*/
void setSpeed(unsigned int whatSpeed);
/*!
* \brief reads out the currently selected speed in revolutions per minute.
* \sa setSpeed()
*/
unsigned int getSpeed(void);
/*!
* \brief Set the number of microsteps in 2^i values (rounded) up to 256
*
* This method set's the number of microsteps per step in 2^i interval.
* This means you can select 1, 2, 4, 16, 32, 64, 128 or 256 as valid microsteps.
* If you give any other value it will be rounded to the next smaller number (3 would give a microstepping of 2).
* You can always check the current microstepping with getMicrosteps().
*/
void setMicrosteps(int number_of_steps);
/*!
* \brief returns the effective current number of microsteps selected.
*
* This function always returns the effective number of microsteps.
* This can be a bit different than the micro steps set in setMicrosteps() since it is rounded to 2^i.
*
* \sa setMicrosteps()
*/
int getMicrosteps(void);
/*!
* \brief Initiate a movement for the given number of steps. Positive numbers move in one, negative numbers in the other direction.
*
* \param number_of_steps The number of steps to move the motor.
* \return 0 if the motor was not moving and moves now. -1 if the motor is moving and the new steps could not be set.
*
* If the previous movement is not finished yet the function will return -1 and not change the steps to move the motor.
* If the motor does not move it return 0
*
* The direction of the movement is indicated by the sign of the steps parameter. It is not determinable if positive values are right
* or left This depends on the internal construction of the motor and how you connected it to the stepper driver.
*
* You can always verify with isMoving() or even use stop() to stop the motor before giving it new step directions.
* \sa isMoving(), getStepsLeft(), stop()
*/
char step(int number_of_steps);
/*!
* \brief Central movement method, must be called as often as possible in the lopp function and is very fast.
*
* This routine checks if the motor still has to move, if the waiting delay has passed to send a new step command to the motor
* and manages the number of steps yet to move to fulfill the current move command.
*
* This function is implemented to be as fast as possible to call it as often as possible in your loop routine.
* The more regurlarly you call this function the better. In both senses of 'regularly': Calling it as often as
* possible is not a bad idea and if you even manage that the intervals you call this function are not too irregular helps too.
*
* You can call this routine even if you know that the motor is not miving. It introduces just a very small penalty in your code.
* You must not call isMoving() to determine if you need to call this function, since taht is done internally already and only
* slows down you code.
*
* How often you call this function directly influences your top miving speed for the motor. It may be a good idea to call this
* from an timer overflow interrupt to ensure proper calling.
* \sa step()
*/
char move(void);
/*!
* \brief checks if the motor still has to move to fulfill the last movement command.
* \return 0 if the motor stops, -1 if the motor is moving.
*
* This method can be used to determine if the motor is ready for new movements.
*\sa step(), move()
*/
char isMoving(void);
/*!
* \brief Get the number of steps left in the current movement.
* \return The number of steps left in the movement. This number is always positive.
*/
unsigned int getStepsLeft(void);
/*!
* \brief Stops the motor regardless if it moves or not.
* \return -1 if the motor was moving and is really stoped or 0 if it was not moving at all.
*
* This method directly and apruptely stops the motor and may be used as an emergency stop.
*/
char stop(void);
/*!
* \brief Sets and configure the classical Constant Off Timer Chopper
* \param constant_off_time The off time setting controls the minimum chopper frequency. For most applications an off time within the range of 5μs to 20μs will fit. Setting this parameter to zero completely disables all driver transistors and the motor can free-wheel. 0: chopper off, 1:15: off time setting (1 will work with minimum blank time of 24 clocks)
* \param blank_time Selects the comparator blank time. This time needs to safely cover the switching event and the duration of the ringing on the sense resistor. For most low current drivers, a setting of 1 or 2 is good. For high current applications with large MOSFETs, a setting of 2 or 3 will be required. 0 (min setting) (3) amx setting
* \param fast_decay_time_setting Fast decay time setting. Controls the portion of fast decay for each chopper cycle. 0: slow decay only, 115: duration of fast decay phase
* \param sine_wave_offset Sine wave offset. Controls the sine wave offset. A positive offset corrects for zero crossing error. -3-1: negative offset, 0: no offset,112: positive offset
* \param use_curreent_comparator Selects usage of the current comparator for termination of the fast decay cycle. If current comparator is enabled, it terminates the fast decay cycle in case the current reaches a higher negative value than the actual positive value. (0 disable, -1 enable).
*
* The classic constant off time chopper uses a fixed portion of fast decay following each on phase.
* While the duration of the on time is determined by the chopper comparator, the fast decay time needs
* to be set by the user in a way, that the current decay is enough for the driver to be able to follow
* the falling slope of the sine wave, and on the other hand it should not be too long, in order to minimize
* motor current ripple and power dissipation. This best can be tuned using an oscilloscope or
* trying out motor smoothness at different velocities. A good starting value is a fast decay time setting
* similar to the slow decay time setting.
* After tuning of the fast decay time, the offset should be determined, in order to have a smooth zero transition.
* This is necessary, because the fast decay phase leads to the absolute value of the motor current being lower
* than the target current (see figure 17). If the zero offset is too low, the motor stands still for a short
* moment during current zero crossing, if it is set too high, it makes a larger microstep.
* Typically, a positive offset setting is required for optimum operation.
*
* \sa setSpreadCycleChoper() for other alternatives.
* \sa setRandomOffTime() for spreading the noise over a wider spectrum
*/
void setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, unsigned char use_current_comparator);
/*!
* \brief Sets and configures with spread cycle chopper.
* \param constant_off_time The off time setting controls the minimum chopper frequency. For most applications an off time within the range of 5μs to 20μs will fit. Setting this parameter to zero completely disables all driver transistors and the motor can free-wheel. 0: chopper off, 1:15: off time setting (1 will work with minimum blank time of 24 clocks)
* \param blank_time Selects the comparator blank time. This time needs to safely cover the switching event and the duration of the ringing on the sense resistor. For most low current drivers, a setting of 1 or 2 is good. For high current applications with large MOSFETs, a setting of 2 or 3 will be required. 0 (min setting) (3) amx setting
* \param hysteresis_start Hysteresis start setting. Please remark, that this value is an offset to the hysteresis end value. 1 8
* \param hysteresis_end Hysteresis end setting. Sets the hysteresis end value after a number of decrements. Decrement interval time is controlled by hysteresis_decrement. The sum hysteresis_start + hysteresis_end must be <16. At a current setting CS of max. 30 (amplitude reduced to 240), the sum is not limited.
* \param hysteresis_decrement Hysteresis decrement setting. This setting determines the slope of the hysteresis during on time and during fast decay time. 0 (fast decrement) 3 (slow decrement).
*
* The spreadCycle chopper scheme (pat.fil.) is a precise and simple to use chopper principle, which automatically determines
* the optimum fast decay portion for the motor. Anyhow, a number of settings can be made in order to optimally fit the driver
* to the motor.
* Each chopper cycle is comprised of an on-phase, a slow decay phase, a fast decay phase and a second slow decay phase.
* The slow decay phases limit the maximum chopper frequency and are important for low motor and driver power dissipation.
* The hysteresis start setting limits the chopper frequency by forcing the driver to introduce a minimum amount of
* current ripple into the motor coils. The motor inductivity determines the ability to follow a changing motor current.
* The duration of the on- and fast decay phase needs to cover at least the blank time, because the current comparator is
* disabled during this time.
*
* \sa setRandomOffTime() for spreading the noise over a wider spectrum
*/
void setSpreadCycleChopper(char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement);
/*!
* \brief Use random off time for noise reduction (0 for off, -1 for on).
* \param value 0 for off, -1 for on
*
* In a constant off time chopper scheme both coil choppers run freely, i.e. are not synchronized.
* The frequency of each chopper mainly depends on the coil current and the position dependant motor coil inductivity,
* thus it depends on the microstep position. With some motors a slightly audible beat can occur between the chopper
* frequencies, especially when they are near to each other. This typically occurs at a few microstep positions within
* each quarter wave.
* This effect normally is not audible when compared to mechanical noise generated by ball bearings,
* etc. Further factors which can cause a similar effect are a poor layout of sense resistor GND connection.
* In order to minimize the effect of a beat between both chopper frequencies, an internal random generator is provided.
* It modulates the slow decay time setting when switched on. The random off time feature further spreads the chopper spectrum,
* reducing electromagnetic emission on single frequencies.
*/
void setRandomOffTime(char value);
/*!
* \brief set the maximum motor current in mA (1000 is 1 Amp)
* Keep in mind this is the maximum peak Current. The RMS current will be 1/sqrt(2) smaller. The actual current can also be smaller
* by employing CoolStep.
* \param current the maximum motor current in mA
* \sa getCurrent(), getCurrentCurrent()
*/
void setCurrent(unsigned int current);
/*!
* \brief readout the motor maximum current in mA (1000 is an Amp)
* This is the maximum current. to get the current current - which may be affected by CoolStep us getCurrentCurrent()
*\return the maximum motor current in milli amps
* \sa getCurrentCurrent()
*/
unsigned int getCurrent(void);
/*!
* \brief set the StallGuard threshold in order to get sensible StallGuard readings.
* \param stall_guard_threshold -64 63 the StallGuard threshold
* \param stall_guard_filter_enabled 0 if the filter is disabled, -1 if it is enabled
*
* The StallGuard threshold is used to optimize the StallGuard reading to sensible values. It should be at 0 at
* the maximum allowable load on the otor (but not before). = is a good starting point (and the default)
* If you get Stall Gaurd readings of 0 without any load or with too little laod increase the value.
* If you get readings of 1023 even with load decrease the setting.
*
* If you switch on the filter the StallGuard reading is only updated each 4th full step to reduce the noise in the
* reading.
*
* \sa getCurrentStallGuardReading() to read out the current value.
*/
void setStallGuardThreshold(char stall_guard_threshold, char stall_guard_filter_enabled);
/*!
* \brief reads out the StallGuard threshold
* \return a number between -64 and 63.
*/
char getStallGuardThreshold(void);
/*!
* \brief returns the current setting of the StallGuard filter
* \return 0 if not set, -1 if set
*/
char getStallGuardFilter(void);
/*!
* \brief This method configures the CoolStep smart energy operation. You must have a proper StallGuard configuration for the motor situation (current, voltage, speed) in rder to use this feature.
* \param lower_SG_threshold Sets the lower threshold for stallGuard2TM reading. Below this value, the motor current becomes increased. Allowed values are 0...480
* \param SG_hysteresis Sets the distance between the lower and the upper threshold for stallGuard2TM reading. Above the upper threshold (which is lower_SG_threshold+SG_hysteresis+1) the motor current becomes decreased. Allowed values are 0...480
* \param current_decrement_step_size Sets the current decrement steps. If the StallGuard value is above the threshold the current gets decremented by this step size. 0...32
* \param current_increment_step_size Sets the current increment step. The current becomes incremented for each measured stallGuard2TM value below the lower threshold. 0...8
* \param lower_current_limit Sets the lower motor current limit for coolStepTM operation by scaling the CS value. Values can be COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
* The CoolStep smart energy operation automatically adjust the current sent into the motor according to the current load,
* read out by the StallGuard in order to provide the optimum torque with the minimal current consumption.
* You configure the CoolStep current regulator by defining upper and lower bounds of StallGuard readouts. If the readout is above the
* limit the current gets increased, below the limit the current gets decreased.
* You can specify the upper an lower threshold of the StallGuard readout in order to adjust the current. You can also set the number of
* StallGuard readings neccessary above or below the limit to get a more stable current adjustement.
* The current adjustement itself is configured by the number of steps the current gests in- or decreased and the absolut minimum current
* (1/2 or 1/4th otf the configured current).
* \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
*/
void setCoolStepConfiguration(unsigned int lower_SG_threshold, unsigned int SG_hysteresis, unsigned char current_decrement_step_size,
unsigned char current_increment_step_size, unsigned char lower_current_limit);
/*!
* \brief enables or disables the CoolStep smart energy operation feature. It must be configured before enabling it.
* \param enabled true if CoolStep should be enabled, false if not.
* \sa setCoolStepConfiguration()
*/
void setCoolStepEnabled(boolean enabled);
/*!
* \brief check if the CoolStep feature is enabled
* \sa setCoolStepEnabled()
*/
boolean isCoolStepEnabled();
/*!
* \brief returns the lower StallGuard threshold for the CoolStep operation
* \sa setCoolStepConfiguration()
*/
unsigned int getCoolStepLowerSgThreshold();
/*!
* \brief returns the upper StallGuard threshold for the CoolStep operation
* \sa setCoolStepConfiguration()
*/
unsigned int getCoolStepUpperSgThreshold();
/*!
* \brief returns the number of StallGuard readings befor CoolStep adjusts the motor current.
* \sa setCoolStepConfiguration()
*/
unsigned char getCoolStepNumberOfSGReadings();
/*!
* \brief returns the increment steps for the current for the CoolStep operation
* \sa setCoolStepConfiguration()
*/
unsigned char getCoolStepCurrentIncrementSize();
/*!
* \brief returns the absolut minium current for the CoolStep operation
* \sa setCoolStepConfiguration()
* \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
*/
unsigned char getCoolStepLowerCurrentLimit();
/*!
* \brief Get the current microstep position for phase A
* \return The current microstep position for phase A 0255
*
* Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time.
*/
int getMotorPosition(void);
/*!
* \brief Reads the current StallGuard value.
* \return The current StallGuard value, lesser values indicate higher load, 0 means stall detected.
* Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time.
* \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
*/
int getCurrentStallGuardReading(void);
/*!
* \brief Reads the current current setting value as fraction of the maximum current
* Returns values between 0 and 31, representing 1/32 to 32/32 (=1)
* \sa setCoolStepConfiguration()
*/
unsigned char getCurrentCSReading(void);
/*!
*\brief a convenience method to determine if the current scaling uses 0.31V or 0.165V as reference.
*\return false if 0.13V is the reference voltage, true if 0.165V is used.
*/
boolean isCurrentScalingHalfed();
/*!
* \brief Reads the current current setting value and recalculates the absolute current in mA (1A would be 1000).
* This method calculates the currently used current setting (either by setting or by CoolStep) and reconstructs
* the current in mA by usinge the VSENSE and resistor value. This method uses floating point math - so it
* may not be the fastest.
* \sa getCurrentCSReading(), getResistor(), isCurrentScalingHalfed(), getCurrent()
*/
unsigned int getCurrentCurrent(void);
/*!
* \brief checks if there is a StallGuard warning in the last status
* \return 0 if there was no warning, -1 if there was some warning.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*
* \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
*/
boolean isStallGuardOverThreshold(void);
/*!
* \brief Return over temperature status of the last status readout
* return 0 is everything is OK, TMC26X_OVERTEMPERATURE_PREWARING if status is reached, TMC26X_OVERTEMPERATURE_SHUTDOWN is the chip is shutdown, -1 if the status is unknown.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
char getOverTemperature(void);
/*!
* \brief Is motor channel A shorted to ground detected in the last status readout.
* \return true is yes, false if not.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isShortToGroundA(void);
/*!
* \brief Is motor channel B shorted to ground detected in the last status readout.
* \return true is yes, false if not.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isShortToGroundB(void);
/*!
* \brief iIs motor channel A connected according to the last statu readout.
* \return true is yes, false if not.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isOpenLoadA(void);
/*!
* \brief iIs motor channel A connected according to the last statu readout.
* \return true is yes, false if not.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isOpenLoadB(void);
/*!
* \brief Is chopper inactive since 2^20 clock cycles - defaults to ~0,08s
* \return true is yes, false if not.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isStandStill(void);
/*!
* \brief checks if there is a StallGuard warning in the last status
* \return 0 if there was no warning, -1 if there was some warning.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*
* \sa isStallGuardOverThreshold()
* TODO why?
*
* \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
*/
boolean isStallGuardReached(void);
/*!
*\brief enables or disables the motor driver bridges. If disabled the motor can run freely. If enabled not.
*\param enabled a boolean value true if the motor should be enabled, false otherwise.
*/
void setEnabled(boolean enabled);
/*!
*\brief checks if the output bridges are enabled. If the bridges are not enabled the motor can run freely
*\return true if the bridges and by that the motor driver are enabled, false if not.
*\sa setEnabled()
*/
boolean isEnabled();
/*!
* \brief Manually read out the status register
* This function sends a byte to the motor driver in order to get the current readout. The parameter read_value
* seletcs which value will get returned. If the read_vlaue changes in respect to the previous readout this method
* automatically send two bytes to the motor: one to set the redout and one to get the actual readout. So this method
* may take time to send and read one or two bits - depending on the previous readout.
* \param read_value selects which value to read out (0..3). You can use the defines TMC26X_READOUT_POSITION, TMC_262_READOUT_STALLGUARD, or TMC_262_READOUT_CURRENT
* \sa TMC26X_READOUT_POSITION, TMC_262_READOUT_STALLGUARD, TMC_262_READOUT_CURRENT
*/
void readStatus(char read_value);
/*!
* \brief Returns the current sense resistor value in milliohm.
* The default value of ,15 Ohm will return 150.
*/
int getResistor();
/*!
* \brief Prints out all the information that can be found in the last status read out - it does not force a status readout.
* The result is printed via Serial
*/
void debugLastStatus(void);
/*!
* \brief library version
* \return the version number as int.
*/
int version(void);
private:
unsigned int steps_left; //the steps the motor has to do to complete the movement
int direction; // Direction of rotation
unsigned long step_delay; // delay between steps, in ms, based on speed
int number_of_steps; // total number of steps this motor can take
unsigned int speed; // we need to store the current speed in order to change the speed after changing microstepping
unsigned int resistor; //current sense resitor value in milliohm
unsigned long last_step_time; // time stamp in ms of when the last step was taken
unsigned long next_step_time; // time stamp in ms of when the last step was taken
//driver control register copies to easily set & modify the registers
unsigned long driver_control_register_value;
unsigned long chopper_config_register;
unsigned long cool_step_register_value;
unsigned long stall_guard2_current_register_value;
unsigned long driver_configuration_register_value;
//the driver status result
unsigned long driver_status_result;
//helper routione to get the top 10 bit of the readout
inline int getReadoutValue();
//the pins for the stepper driver
unsigned char cs_pin;
unsigned char step_pin;
unsigned char dir_pin;
//status values
boolean started; //if the stepper has been started yet
int microsteps; //the current number of micro steps
char constant_off_time; //we need to remember this value in order to enable and disable the motor
unsigned char cool_step_lower_threshold; // we need to remember the threshold to enable and disable the CoolStep feature
boolean cool_step_enabled; //we need to remember this to configure the coolstep if it si enabled
//SPI sender
inline void send262(unsigned long datagram);
};
#endif

View file

@ -0,0 +1,848 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<title>Trinamic TMC26X Stepper Driver for Arduino: TMC26XStepper.cpp File Reference</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td style="padding-left: 0.5em;">
<div id="projectname">Trinamic TMC26X Stepper Driver for Arduino
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- Generated by Doxygen 1.7.6.1 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li class="current"><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li><a href="files.html"><span>File&#160;List</span></a></li>
<li><a href="globals.html"><span>File&#160;Members</span></a></li>
</ul>
</div>
</div>
<div class="header">
<div class="summary">
<a href="#define-members">Defines</a> </div>
<div class="headertitle">
<div class="title">TMC26XStepper.cpp File Reference</div> </div>
</div><!--header-->
<div class="contents">
<div class="textblock"><code>#include &lt;WProgram.h&gt;</code><br/>
<code>#include &lt;SPI.h&gt;</code><br/>
<code>#include &quot;<a class="el" href="_t_m_c26_x_stepper_8h_source.html">TMC26XStepper.h</a>&quot;</code><br/>
</div>
<p><a href="_t_m_c26_x_stepper_8cpp_source.html">Go to the source code of this file.</a></p>
<table class="memberdecls">
<tr><td colspan="2"><h2><a name="define-members"></a>
Defines</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a6560b3471273e99e280ba795e3469ede">DEFAULT_MICROSTEPPING_VALUE</a>&#160;&#160;&#160;32</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a108f18bf4a30a0e0f0991ac0e4ce0579">DRIVER_CONTROL_REGISTER</a>&#160;&#160;&#160;0x0ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a70a540d1090b989b8600b5e4776659fe">CHOPPER_CONFIG_REGISTER</a>&#160;&#160;&#160;0x80000ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab9828bfaa075a0a8647c709136016317">COOL_STEP_REGISTER</a>&#160;&#160;&#160;0xA0000ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a478d9bde09a6528eef6af6ffeeb6caba">STALL_GUARD2_LOAD_MEASURE_REGISTER</a>&#160;&#160;&#160;0xC0000ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#af35f569d42ea3b1d634901a3b6a908ee">DRIVER_CONFIG_REGISTER</a>&#160;&#160;&#160;0xE0000ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a3b02ee1f518b0c90c16488f937abd443">REGISTER_BIT_PATTERN</a>&#160;&#160;&#160;0xFFFFFul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8f5cb0c066109ffb18cefc0e85ee1d1b">MICROSTEPPING_PATTERN</a>&#160;&#160;&#160;0xFul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa64245f223209654c60588e4558e0bab">STEP_INTERPOLATION</a>&#160;&#160;&#160;0x200ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a770601bf0153e4bc639b9c3005b15af7">DOUBLE_EDGE_STEP</a>&#160;&#160;&#160;0x100ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a4fb1c008e2ff76eee9362600eed112e1">VSENSE</a>&#160;&#160;&#160;0x40ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a143b7757272f07866d9655bde8303d9a">READ_MICROSTEP_POSTION</a>&#160;&#160;&#160;0x0ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac1bd4da94fab7ce1049be2f866211819">READ_STALL_GUARD_READING</a>&#160;&#160;&#160;0x10ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#aef62b7fdcbac0b33b2d6e9cea4b5f9b2">READ_STALL_GUARD_AND_COOL_STEP</a>&#160;&#160;&#160;0x20ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a88a4b45fa6385eba8aa4f0342334b832">READ_SELECTION_PATTERN</a>&#160;&#160;&#160;0x30ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a57418a67ff726d540b813230bca1d536">CHOPPER_MODE_STANDARD</a>&#160;&#160;&#160;0x0ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#aaf1b564ced7de8ff3245c964e3775826">CHOPPER_MODE_T_OFF_FAST_DECAY</a>&#160;&#160;&#160;0x4000ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa4e49237f2671e7f28aa34ae0e89da8d">T_OFF_PATTERN</a>&#160;&#160;&#160;0xful</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a64520580cffd416668f3b91bd60f84e1">RANDOM_TOFF_TIME</a>&#160;&#160;&#160;0x2000ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a42cb2ce84258587d514ec3268548ba89">BLANK_TIMING_PATTERN</a>&#160;&#160;&#160;0x18000ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#abdac78f7f2c506972265a8e5883e1eae">BLANK_TIMING_SHIFT</a>&#160;&#160;&#160;15</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a424c248097b38c1e29e6a58ad48e6bd9">HYSTERESIS_DECREMENT_PATTERN</a>&#160;&#160;&#160;0x1800ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a36e554a87785ce6ba998b79aae9e74e0">HYSTERESIS_DECREMENT_SHIFT</a>&#160;&#160;&#160;11</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ad9d2302f6d61cd84a612a2e2bcdeb56e">HYSTERESIS_LOW_VALUE_PATTERN</a>&#160;&#160;&#160;0x780ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a38ce0bb0fa20db28351ac9167f28db98">HYSTERESIS_LOW_SHIFT</a>&#160;&#160;&#160;7</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a0de4e98b412dced62c3a4452b7483af3">HYSTERESIS_START_VALUE_PATTERN</a>&#160;&#160;&#160;0x78ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac2c1c939256126e605396c4aaee3c804">HYSTERESIS_START_VALUE_SHIFT</a>&#160;&#160;&#160;4</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a7659d842c803e47ba911a2a6e26327f3">T_OFF_TIMING_PATERN</a>&#160;&#160;&#160;0xFul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8a261a77d198b85f6dd8416387b354b3">MINIMUM_CURRENT_FOURTH</a>&#160;&#160;&#160;0x8000ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#adbe13a0464355e42fbe786ca5f58ed8d">CURRENT_DOWN_STEP_SPEED_PATTERN</a>&#160;&#160;&#160;0x6000ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac8f748bf735c447dbed7dd4c7b631a87">SE_MAX_PATTERN</a>&#160;&#160;&#160;0xF00ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#aba6c07e5672e34e618bb3a550ab0d2bc">SE_CURRENT_STEP_WIDTH_PATTERN</a>&#160;&#160;&#160;0x60ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae1862dfb958c03698b0abd95fda033ea">SE_MIN_PATTERN</a>&#160;&#160;&#160;0xful</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#afdbbefabd0c29c4b6e403c4663d0f0be">STALL_GUARD_FILTER_ENABLED</a>&#160;&#160;&#160;0x10000ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae631457932894a974334892704550ecc">STALL_GUARD_TRESHHOLD_VALUE_PATTERN</a>&#160;&#160;&#160;0x17F00ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a99dcb8c6d98b0b54c23699a3f90450e4">CURRENT_SCALING_PATTERN</a>&#160;&#160;&#160;0x1Ful</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a99ac04f0615556fc13c0c9f3e1c1b49d">STALL_GUARD_CONFIG_PATTERN</a>&#160;&#160;&#160;0x17F00ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a6a1cb1fd61cf7c570f94376fa11fe55b">STALL_GUARD_VALUE_PATTERN</a>&#160;&#160;&#160;0x7F00ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa09ef662fd19bf2d063d6bd0f48eca14">STATUS_STALL_GUARD_STATUS</a>&#160;&#160;&#160;0x1ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#adbb23d2f055c9eab55eac29d1a75deb4">STATUS_OVER_TEMPERATURE_SHUTDOWN</a>&#160;&#160;&#160;0x2ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa317fd77f2f26fdfbfd331e21d9069e8">STATUS_OVER_TEMPERATURE_WARNING</a>&#160;&#160;&#160;0x4ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8e03041302a092174fa33b3cf837dca2">STATUS_SHORT_TO_GROUND_A</a>&#160;&#160;&#160;0x8ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a903c3eba99695a32c6736463dcfd93ae">STATUS_SHORT_TO_GROUND_B</a>&#160;&#160;&#160;0x10ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae9cbbe5af7188e6bff8fe412f8e42f59">STATUS_OPEN_LOAD_A</a>&#160;&#160;&#160;0x20ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab29dc5cd6c6c4e5bf99e71bd563e1be1">STATUS_OPEN_LOAD_B</a>&#160;&#160;&#160;0x40ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab96ed1635faee6650e9cce73598a2773">STATUS_STAND_STILL</a>&#160;&#160;&#160;0x80ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a5c3d76da63f585e37813c32be2e11ab7">READOUT_VALUE_PATTERN</a>&#160;&#160;&#160;0xFFC00ul</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a54a6d12e96d851361974b10614a00e45">INITIAL_MICROSTEPPING</a>&#160;&#160;&#160;0x3ul</td></tr>
</table>
<hr/><h2>Define Documentation</h2>
<a class="anchor" id="a42cb2ce84258587d514ec3268548ba89"></a><!-- doxytag: member="TMC26XStepper.cpp::BLANK_TIMING_PATTERN" ref="a42cb2ce84258587d514ec3268548ba89" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a42cb2ce84258587d514ec3268548ba89">BLANK_TIMING_PATTERN</a>&#160;&#160;&#160;0x18000ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00063">63</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="abdac78f7f2c506972265a8e5883e1eae"></a><!-- doxytag: member="TMC26XStepper.cpp::BLANK_TIMING_SHIFT" ref="abdac78f7f2c506972265a8e5883e1eae" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#abdac78f7f2c506972265a8e5883e1eae">BLANK_TIMING_SHIFT</a>&#160;&#160;&#160;15</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00064">64</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a70a540d1090b989b8600b5e4776659fe"></a><!-- doxytag: member="TMC26XStepper.cpp::CHOPPER_CONFIG_REGISTER" ref="a70a540d1090b989b8600b5e4776659fe" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a70a540d1090b989b8600b5e4776659fe">CHOPPER_CONFIG_REGISTER</a>&#160;&#160;&#160;0x80000ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00041">41</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a57418a67ff726d540b813230bca1d536"></a><!-- doxytag: member="TMC26XStepper.cpp::CHOPPER_MODE_STANDARD" ref="a57418a67ff726d540b813230bca1d536" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a57418a67ff726d540b813230bca1d536">CHOPPER_MODE_STANDARD</a>&#160;&#160;&#160;0x0ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00059">59</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="aaf1b564ced7de8ff3245c964e3775826"></a><!-- doxytag: member="TMC26XStepper.cpp::CHOPPER_MODE_T_OFF_FAST_DECAY" ref="aaf1b564ced7de8ff3245c964e3775826" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aaf1b564ced7de8ff3245c964e3775826">CHOPPER_MODE_T_OFF_FAST_DECAY</a>&#160;&#160;&#160;0x4000ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00060">60</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="ab9828bfaa075a0a8647c709136016317"></a><!-- doxytag: member="TMC26XStepper.cpp::COOL_STEP_REGISTER" ref="ab9828bfaa075a0a8647c709136016317" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab9828bfaa075a0a8647c709136016317">COOL_STEP_REGISTER</a>&#160;&#160;&#160;0xA0000ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00042">42</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="adbe13a0464355e42fbe786ca5f58ed8d"></a><!-- doxytag: member="TMC26XStepper.cpp::CURRENT_DOWN_STEP_SPEED_PATTERN" ref="adbe13a0464355e42fbe786ca5f58ed8d" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#adbe13a0464355e42fbe786ca5f58ed8d">CURRENT_DOWN_STEP_SPEED_PATTERN</a>&#160;&#160;&#160;0x6000ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00075">75</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a99dcb8c6d98b0b54c23699a3f90450e4"></a><!-- doxytag: member="TMC26XStepper.cpp::CURRENT_SCALING_PATTERN" ref="a99dcb8c6d98b0b54c23699a3f90450e4" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a99dcb8c6d98b0b54c23699a3f90450e4">CURRENT_SCALING_PATTERN</a>&#160;&#160;&#160;0x1Ful</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00083">83</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a6560b3471273e99e280ba795e3469ede"></a><!-- doxytag: member="TMC26XStepper.cpp::DEFAULT_MICROSTEPPING_VALUE" ref="a6560b3471273e99e280ba795e3469ede" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a6560b3471273e99e280ba795e3469ede">DEFAULT_MICROSTEPPING_VALUE</a>&#160;&#160;&#160;32</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00037">37</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a770601bf0153e4bc639b9c3005b15af7"></a><!-- doxytag: member="TMC26XStepper.cpp::DOUBLE_EDGE_STEP" ref="a770601bf0153e4bc639b9c3005b15af7" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a770601bf0153e4bc639b9c3005b15af7">DOUBLE_EDGE_STEP</a>&#160;&#160;&#160;0x100ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00051">51</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="af35f569d42ea3b1d634901a3b6a908ee"></a><!-- doxytag: member="TMC26XStepper.cpp::DRIVER_CONFIG_REGISTER" ref="af35f569d42ea3b1d634901a3b6a908ee" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#af35f569d42ea3b1d634901a3b6a908ee">DRIVER_CONFIG_REGISTER</a>&#160;&#160;&#160;0xE0000ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00044">44</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a108f18bf4a30a0e0f0991ac0e4ce0579"></a><!-- doxytag: member="TMC26XStepper.cpp::DRIVER_CONTROL_REGISTER" ref="a108f18bf4a30a0e0f0991ac0e4ce0579" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a108f18bf4a30a0e0f0991ac0e4ce0579">DRIVER_CONTROL_REGISTER</a>&#160;&#160;&#160;0x0ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00040">40</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a424c248097b38c1e29e6a58ad48e6bd9"></a><!-- doxytag: member="TMC26XStepper.cpp::HYSTERESIS_DECREMENT_PATTERN" ref="a424c248097b38c1e29e6a58ad48e6bd9" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a424c248097b38c1e29e6a58ad48e6bd9">HYSTERESIS_DECREMENT_PATTERN</a>&#160;&#160;&#160;0x1800ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00065">65</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a36e554a87785ce6ba998b79aae9e74e0"></a><!-- doxytag: member="TMC26XStepper.cpp::HYSTERESIS_DECREMENT_SHIFT" ref="a36e554a87785ce6ba998b79aae9e74e0" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a36e554a87785ce6ba998b79aae9e74e0">HYSTERESIS_DECREMENT_SHIFT</a>&#160;&#160;&#160;11</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00066">66</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a38ce0bb0fa20db28351ac9167f28db98"></a><!-- doxytag: member="TMC26XStepper.cpp::HYSTERESIS_LOW_SHIFT" ref="a38ce0bb0fa20db28351ac9167f28db98" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a38ce0bb0fa20db28351ac9167f28db98">HYSTERESIS_LOW_SHIFT</a>&#160;&#160;&#160;7</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00068">68</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="ad9d2302f6d61cd84a612a2e2bcdeb56e"></a><!-- doxytag: member="TMC26XStepper.cpp::HYSTERESIS_LOW_VALUE_PATTERN" ref="ad9d2302f6d61cd84a612a2e2bcdeb56e" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ad9d2302f6d61cd84a612a2e2bcdeb56e">HYSTERESIS_LOW_VALUE_PATTERN</a>&#160;&#160;&#160;0x780ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00067">67</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a0de4e98b412dced62c3a4452b7483af3"></a><!-- doxytag: member="TMC26XStepper.cpp::HYSTERESIS_START_VALUE_PATTERN" ref="a0de4e98b412dced62c3a4452b7483af3" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a0de4e98b412dced62c3a4452b7483af3">HYSTERESIS_START_VALUE_PATTERN</a>&#160;&#160;&#160;0x78ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00069">69</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="ac2c1c939256126e605396c4aaee3c804"></a><!-- doxytag: member="TMC26XStepper.cpp::HYSTERESIS_START_VALUE_SHIFT" ref="ac2c1c939256126e605396c4aaee3c804" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac2c1c939256126e605396c4aaee3c804">HYSTERESIS_START_VALUE_SHIFT</a>&#160;&#160;&#160;4</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00070">70</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a54a6d12e96d851361974b10614a00e45"></a><!-- doxytag: member="TMC26XStepper.cpp::INITIAL_MICROSTEPPING" ref="a54a6d12e96d851361974b10614a00e45" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a54a6d12e96d851361974b10614a00e45">INITIAL_MICROSTEPPING</a>&#160;&#160;&#160;0x3ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00099">99</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a8f5cb0c066109ffb18cefc0e85ee1d1b"></a><!-- doxytag: member="TMC26XStepper.cpp::MICROSTEPPING_PATTERN" ref="a8f5cb0c066109ffb18cefc0e85ee1d1b" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8f5cb0c066109ffb18cefc0e85ee1d1b">MICROSTEPPING_PATTERN</a>&#160;&#160;&#160;0xFul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00049">49</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a8a261a77d198b85f6dd8416387b354b3"></a><!-- doxytag: member="TMC26XStepper.cpp::MINIMUM_CURRENT_FOURTH" ref="a8a261a77d198b85f6dd8416387b354b3" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8a261a77d198b85f6dd8416387b354b3">MINIMUM_CURRENT_FOURTH</a>&#160;&#160;&#160;0x8000ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00074">74</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a64520580cffd416668f3b91bd60f84e1"></a><!-- doxytag: member="TMC26XStepper.cpp::RANDOM_TOFF_TIME" ref="a64520580cffd416668f3b91bd60f84e1" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a64520580cffd416668f3b91bd60f84e1">RANDOM_TOFF_TIME</a>&#160;&#160;&#160;0x2000ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00062">62</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a143b7757272f07866d9655bde8303d9a"></a><!-- doxytag: member="TMC26XStepper.cpp::READ_MICROSTEP_POSTION" ref="a143b7757272f07866d9655bde8303d9a" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a143b7757272f07866d9655bde8303d9a">READ_MICROSTEP_POSTION</a>&#160;&#160;&#160;0x0ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00053">53</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a88a4b45fa6385eba8aa4f0342334b832"></a><!-- doxytag: member="TMC26XStepper.cpp::READ_SELECTION_PATTERN" ref="a88a4b45fa6385eba8aa4f0342334b832" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a88a4b45fa6385eba8aa4f0342334b832">READ_SELECTION_PATTERN</a>&#160;&#160;&#160;0x30ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00056">56</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="aef62b7fdcbac0b33b2d6e9cea4b5f9b2"></a><!-- doxytag: member="TMC26XStepper.cpp::READ_STALL_GUARD_AND_COOL_STEP" ref="aef62b7fdcbac0b33b2d6e9cea4b5f9b2" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aef62b7fdcbac0b33b2d6e9cea4b5f9b2">READ_STALL_GUARD_AND_COOL_STEP</a>&#160;&#160;&#160;0x20ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00055">55</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="ac1bd4da94fab7ce1049be2f866211819"></a><!-- doxytag: member="TMC26XStepper.cpp::READ_STALL_GUARD_READING" ref="ac1bd4da94fab7ce1049be2f866211819" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac1bd4da94fab7ce1049be2f866211819">READ_STALL_GUARD_READING</a>&#160;&#160;&#160;0x10ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00054">54</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a5c3d76da63f585e37813c32be2e11ab7"></a><!-- doxytag: member="TMC26XStepper.cpp::READOUT_VALUE_PATTERN" ref="a5c3d76da63f585e37813c32be2e11ab7" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a5c3d76da63f585e37813c32be2e11ab7">READOUT_VALUE_PATTERN</a>&#160;&#160;&#160;0xFFC00ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00096">96</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a3b02ee1f518b0c90c16488f937abd443"></a><!-- doxytag: member="TMC26XStepper.cpp::REGISTER_BIT_PATTERN" ref="a3b02ee1f518b0c90c16488f937abd443" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a3b02ee1f518b0c90c16488f937abd443">REGISTER_BIT_PATTERN</a>&#160;&#160;&#160;0xFFFFFul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00046">46</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="aba6c07e5672e34e618bb3a550ab0d2bc"></a><!-- doxytag: member="TMC26XStepper.cpp::SE_CURRENT_STEP_WIDTH_PATTERN" ref="aba6c07e5672e34e618bb3a550ab0d2bc" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aba6c07e5672e34e618bb3a550ab0d2bc">SE_CURRENT_STEP_WIDTH_PATTERN</a>&#160;&#160;&#160;0x60ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00077">77</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="ac8f748bf735c447dbed7dd4c7b631a87"></a><!-- doxytag: member="TMC26XStepper.cpp::SE_MAX_PATTERN" ref="ac8f748bf735c447dbed7dd4c7b631a87" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac8f748bf735c447dbed7dd4c7b631a87">SE_MAX_PATTERN</a>&#160;&#160;&#160;0xF00ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00076">76</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="ae1862dfb958c03698b0abd95fda033ea"></a><!-- doxytag: member="TMC26XStepper.cpp::SE_MIN_PATTERN" ref="ae1862dfb958c03698b0abd95fda033ea" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae1862dfb958c03698b0abd95fda033ea">SE_MIN_PATTERN</a>&#160;&#160;&#160;0xful</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00078">78</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a478d9bde09a6528eef6af6ffeeb6caba"></a><!-- doxytag: member="TMC26XStepper.cpp::STALL_GUARD2_LOAD_MEASURE_REGISTER" ref="a478d9bde09a6528eef6af6ffeeb6caba" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a478d9bde09a6528eef6af6ffeeb6caba">STALL_GUARD2_LOAD_MEASURE_REGISTER</a>&#160;&#160;&#160;0xC0000ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00043">43</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a99ac04f0615556fc13c0c9f3e1c1b49d"></a><!-- doxytag: member="TMC26XStepper.cpp::STALL_GUARD_CONFIG_PATTERN" ref="a99ac04f0615556fc13c0c9f3e1c1b49d" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a99ac04f0615556fc13c0c9f3e1c1b49d">STALL_GUARD_CONFIG_PATTERN</a>&#160;&#160;&#160;0x17F00ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00084">84</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="afdbbefabd0c29c4b6e403c4663d0f0be"></a><!-- doxytag: member="TMC26XStepper.cpp::STALL_GUARD_FILTER_ENABLED" ref="afdbbefabd0c29c4b6e403c4663d0f0be" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#afdbbefabd0c29c4b6e403c4663d0f0be">STALL_GUARD_FILTER_ENABLED</a>&#160;&#160;&#160;0x10000ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00081">81</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="ae631457932894a974334892704550ecc"></a><!-- doxytag: member="TMC26XStepper.cpp::STALL_GUARD_TRESHHOLD_VALUE_PATTERN" ref="ae631457932894a974334892704550ecc" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae631457932894a974334892704550ecc">STALL_GUARD_TRESHHOLD_VALUE_PATTERN</a>&#160;&#160;&#160;0x17F00ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00082">82</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a6a1cb1fd61cf7c570f94376fa11fe55b"></a><!-- doxytag: member="TMC26XStepper.cpp::STALL_GUARD_VALUE_PATTERN" ref="a6a1cb1fd61cf7c570f94376fa11fe55b" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a6a1cb1fd61cf7c570f94376fa11fe55b">STALL_GUARD_VALUE_PATTERN</a>&#160;&#160;&#160;0x7F00ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00085">85</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="ae9cbbe5af7188e6bff8fe412f8e42f59"></a><!-- doxytag: member="TMC26XStepper.cpp::STATUS_OPEN_LOAD_A" ref="ae9cbbe5af7188e6bff8fe412f8e42f59" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae9cbbe5af7188e6bff8fe412f8e42f59">STATUS_OPEN_LOAD_A</a>&#160;&#160;&#160;0x20ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00093">93</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="ab29dc5cd6c6c4e5bf99e71bd563e1be1"></a><!-- doxytag: member="TMC26XStepper.cpp::STATUS_OPEN_LOAD_B" ref="ab29dc5cd6c6c4e5bf99e71bd563e1be1" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab29dc5cd6c6c4e5bf99e71bd563e1be1">STATUS_OPEN_LOAD_B</a>&#160;&#160;&#160;0x40ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00094">94</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="adbb23d2f055c9eab55eac29d1a75deb4"></a><!-- doxytag: member="TMC26XStepper.cpp::STATUS_OVER_TEMPERATURE_SHUTDOWN" ref="adbb23d2f055c9eab55eac29d1a75deb4" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#adbb23d2f055c9eab55eac29d1a75deb4">STATUS_OVER_TEMPERATURE_SHUTDOWN</a>&#160;&#160;&#160;0x2ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00089">89</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="aa317fd77f2f26fdfbfd331e21d9069e8"></a><!-- doxytag: member="TMC26XStepper.cpp::STATUS_OVER_TEMPERATURE_WARNING" ref="aa317fd77f2f26fdfbfd331e21d9069e8" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa317fd77f2f26fdfbfd331e21d9069e8">STATUS_OVER_TEMPERATURE_WARNING</a>&#160;&#160;&#160;0x4ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00090">90</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a8e03041302a092174fa33b3cf837dca2"></a><!-- doxytag: member="TMC26XStepper.cpp::STATUS_SHORT_TO_GROUND_A" ref="a8e03041302a092174fa33b3cf837dca2" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8e03041302a092174fa33b3cf837dca2">STATUS_SHORT_TO_GROUND_A</a>&#160;&#160;&#160;0x8ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00091">91</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a903c3eba99695a32c6736463dcfd93ae"></a><!-- doxytag: member="TMC26XStepper.cpp::STATUS_SHORT_TO_GROUND_B" ref="a903c3eba99695a32c6736463dcfd93ae" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a903c3eba99695a32c6736463dcfd93ae">STATUS_SHORT_TO_GROUND_B</a>&#160;&#160;&#160;0x10ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00092">92</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="aa09ef662fd19bf2d063d6bd0f48eca14"></a><!-- doxytag: member="TMC26XStepper.cpp::STATUS_STALL_GUARD_STATUS" ref="aa09ef662fd19bf2d063d6bd0f48eca14" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa09ef662fd19bf2d063d6bd0f48eca14">STATUS_STALL_GUARD_STATUS</a>&#160;&#160;&#160;0x1ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00088">88</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="ab96ed1635faee6650e9cce73598a2773"></a><!-- doxytag: member="TMC26XStepper.cpp::STATUS_STAND_STILL" ref="ab96ed1635faee6650e9cce73598a2773" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab96ed1635faee6650e9cce73598a2773">STATUS_STAND_STILL</a>&#160;&#160;&#160;0x80ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00095">95</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="aa64245f223209654c60588e4558e0bab"></a><!-- doxytag: member="TMC26XStepper.cpp::STEP_INTERPOLATION" ref="aa64245f223209654c60588e4558e0bab" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa64245f223209654c60588e4558e0bab">STEP_INTERPOLATION</a>&#160;&#160;&#160;0x200ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00050">50</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="aa4e49237f2671e7f28aa34ae0e89da8d"></a><!-- doxytag: member="TMC26XStepper.cpp::T_OFF_PATTERN" ref="aa4e49237f2671e7f28aa34ae0e89da8d" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa4e49237f2671e7f28aa34ae0e89da8d">T_OFF_PATTERN</a>&#160;&#160;&#160;0xful</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00061">61</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a7659d842c803e47ba911a2a6e26327f3"></a><!-- doxytag: member="TMC26XStepper.cpp::T_OFF_TIMING_PATERN" ref="a7659d842c803e47ba911a2a6e26327f3" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a7659d842c803e47ba911a2a6e26327f3">T_OFF_TIMING_PATERN</a>&#160;&#160;&#160;0xFul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00071">71</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="a4fb1c008e2ff76eee9362600eed112e1"></a><!-- doxytag: member="TMC26XStepper.cpp::VSENSE" ref="a4fb1c008e2ff76eee9362600eed112e1" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a4fb1c008e2ff76eee9362600eed112e1">VSENSE</a>&#160;&#160;&#160;0x40ul</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html#l00052">52</a> of file <a class="el" href="_t_m_c26_x_stepper_8cpp_source.html">TMC26XStepper.cpp</a>.</p>
</div>
</div>
</div><!-- contents -->
<hr class="footer"/><address class="footer"><small>
Generated on Mon Nov 19 2012 20:26:21 for Trinamic TMC26X Stepper Driver for Arduino by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.7.6.1
</small></address>
</body>
</html>

View file

@ -0,0 +1,212 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<title>Trinamic TMC26X Stepper Driver for Arduino: TMC26XStepper.h File Reference</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td style="padding-left: 0.5em;">
<div id="projectname">Trinamic TMC26X Stepper Driver for Arduino
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- Generated by Doxygen 1.7.6.1 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li class="current"><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li><a href="files.html"><span>File&#160;List</span></a></li>
<li><a href="globals.html"><span>File&#160;Members</span></a></li>
</ul>
</div>
</div>
<div class="header">
<div class="summary">
<a href="#nested-classes">Classes</a> &#124;
<a href="#define-members">Defines</a> </div>
<div class="headertitle">
<div class="title">TMC26XStepper.h File Reference</div> </div>
</div><!--header-->
<div class="contents">
<p><a href="_t_m_c26_x_stepper_8h_source.html">Go to the source code of this file.</a></p>
<table class="memberdecls">
<tr><td colspan="2"><h2><a name="nested-classes"></a>
Classes</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">class &#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Class representing a TMC26X stepper driver. <a href="class_t_m_c26_x_stepper.html#details">More...</a><br/></td></tr>
<tr><td colspan="2"><h2><a name="define-members"></a>
Defines</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#add42eee34f674f92c19bcd5266d2445f">TMC26X_OVERTEMPERATURE_PREWARING</a>&#160;&#160;&#160;1</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">return value for <a class="el" href="class_t_m_c26_x_stepper.html#a7662c2fbc03d1f5a7da5cabcc153b2d7" title="Return over temperature status of the last status readout return 0 is everything is OK...">TMC26XStepper.getOverTemperature()</a> if there is a overtemperature situation in the TMC chip <a href="#add42eee34f674f92c19bcd5266d2445f"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#adae814ce848677abd87758c7ac79a436">TMC26X_OVERTEMPERATURE_SHUTDOWN</a>&#160;&#160;&#160;2</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">return value for <a class="el" href="class_t_m_c26_x_stepper.html#a7662c2fbc03d1f5a7da5cabcc153b2d7" title="Return over temperature status of the last status readout return 0 is everything is OK...">TMC26XStepper.getOverTemperature()</a> if there is a overtemperature shutdown in the TMC chip <a href="#adae814ce848677abd87758c7ac79a436"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#aff05d4a47ef8821322ccc2a20785fbee">TMC26X_READOUT_POSITION</a>&#160;&#160;&#160;0</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#ac864ff8886123039c7d2d3c617f7ef87">TMC26X_READOUT_STALLGUARD</a>&#160;&#160;&#160;1</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#a01760ad15e3846536526a990efe47094">TMC26X_READOUT_CURRENT</a>&#160;&#160;&#160;3</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#a28b1774bd4aa854fb5e4b6dc7db96ecb">COOL_STEP_HALF_CS_LIMIT</a>&#160;&#160;&#160;0</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">#define&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#a1a4db5eafd0a9247677153cb4c8b7d54">COOL_STEP_QUARTDER_CS_LIMIT</a>&#160;&#160;&#160;1</td></tr>
</table>
<hr/><h2>Define Documentation</h2>
<a class="anchor" id="a28b1774bd4aa854fb5e4b6dc7db96ecb"></a><!-- doxytag: member="TMC26XStepper.h::COOL_STEP_HALF_CS_LIMIT" ref="a28b1774bd4aa854fb5e4b6dc7db96ecb" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8h.html#a28b1774bd4aa854fb5e4b6dc7db96ecb">COOL_STEP_HALF_CS_LIMIT</a>&#160;&#160;&#160;0</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Define to set the minimum current for CoolStep operation to 1/2 of the selected CS minium. </p>
<dl class="see"><dt><b>See also:</b></dt><dd>setCoolStepConfiguration() </dd></dl>
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8h_source.html#l00070">70</a> of file <a class="el" href="_t_m_c26_x_stepper_8h_source.html">TMC26XStepper.h</a>.</p>
</div>
</div>
<a class="anchor" id="a1a4db5eafd0a9247677153cb4c8b7d54"></a><!-- doxytag: member="TMC26XStepper.h::COOL_STEP_QUARTDER_CS_LIMIT" ref="a1a4db5eafd0a9247677153cb4c8b7d54" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8h.html#a1a4db5eafd0a9247677153cb4c8b7d54">COOL_STEP_QUARTDER_CS_LIMIT</a>&#160;&#160;&#160;1</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Define to set the minimum current for CoolStep operation to 1/4 of the selected CS minium. </p>
<dl class="see"><dt><b>See also:</b></dt><dd>setCoolStepConfiguration() </dd></dl>
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8h_source.html#l00075">75</a> of file <a class="el" href="_t_m_c26_x_stepper_8h_source.html">TMC26XStepper.h</a>.</p>
</div>
</div>
<a class="anchor" id="add42eee34f674f92c19bcd5266d2445f"></a><!-- doxytag: member="TMC26XStepper.h::TMC26X_OVERTEMPERATURE_PREWARING" ref="add42eee34f674f92c19bcd5266d2445f" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8h.html#add42eee34f674f92c19bcd5266d2445f">TMC26X_OVERTEMPERATURE_PREWARING</a>&#160;&#160;&#160;1</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>return value for <a class="el" href="class_t_m_c26_x_stepper.html#a7662c2fbc03d1f5a7da5cabcc153b2d7" title="Return over temperature status of the last status readout return 0 is everything is OK...">TMC26XStepper.getOverTemperature()</a> if there is a overtemperature situation in the TMC chip </p>
<p>This warning indicates that the TCM chip is too warm. It is still working but some parameters may be inferior. You should do something against it. </p>
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8h_source.html#l00039">39</a> of file <a class="el" href="_t_m_c26_x_stepper_8h_source.html">TMC26XStepper.h</a>.</p>
</div>
</div>
<a class="anchor" id="adae814ce848677abd87758c7ac79a436"></a><!-- doxytag: member="TMC26XStepper.h::TMC26X_OVERTEMPERATURE_SHUTDOWN" ref="adae814ce848677abd87758c7ac79a436" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8h.html#adae814ce848677abd87758c7ac79a436">TMC26X_OVERTEMPERATURE_SHUTDOWN</a>&#160;&#160;&#160;2</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>return value for <a class="el" href="class_t_m_c26_x_stepper.html#a7662c2fbc03d1f5a7da5cabcc153b2d7" title="Return over temperature status of the last status readout return 0 is everything is OK...">TMC26XStepper.getOverTemperature()</a> if there is a overtemperature shutdown in the TMC chip </p>
<p>This warning indicates that the TCM chip is too warm to operate and has shut down to prevent damage. It will stop working until it cools down again. If you encouter this situation you must do something against it. Like reducing the current or improving the PCB layout and/or heat management. </p>
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8h_source.html#l00047">47</a> of file <a class="el" href="_t_m_c26_x_stepper_8h_source.html">TMC26XStepper.h</a>.</p>
</div>
</div>
<a class="anchor" id="a01760ad15e3846536526a990efe47094"></a><!-- doxytag: member="TMC26XStepper.h::TMC26X_READOUT_CURRENT" ref="a01760ad15e3846536526a990efe47094" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8h.html#a01760ad15e3846536526a990efe47094">TMC26X_READOUT_CURRENT</a>&#160;&#160;&#160;3</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Selects to read out the current current setting (acc. to CoolStep) and the upper bits of the StallGuard value from the motor. </p>
<dl class="see"><dt><b>See also:</b></dt><dd>readStatus(), setCurrent() </dd></dl>
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8h_source.html#l00064">64</a> of file <a class="el" href="_t_m_c26_x_stepper_8h_source.html">TMC26XStepper.h</a>.</p>
</div>
</div>
<a class="anchor" id="aff05d4a47ef8821322ccc2a20785fbee"></a><!-- doxytag: member="TMC26XStepper.h::TMC26X_READOUT_POSITION" ref="aff05d4a47ef8821322ccc2a20785fbee" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8h.html#aff05d4a47ef8821322ccc2a20785fbee">TMC26X_READOUT_POSITION</a>&#160;&#160;&#160;0</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Selects to readout the microstep position from the motor. </p>
<dl class="see"><dt><b>See also:</b></dt><dd>readStatus() </dd></dl>
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8h_source.html#l00054">54</a> of file <a class="el" href="_t_m_c26_x_stepper_8h_source.html">TMC26XStepper.h</a>.</p>
</div>
</div>
<a class="anchor" id="ac864ff8886123039c7d2d3c617f7ef87"></a><!-- doxytag: member="TMC26XStepper.h::TMC26X_READOUT_STALLGUARD" ref="ac864ff8886123039c7d2d3c617f7ef87" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">#define <a class="el" href="_t_m_c26_x_stepper_8h.html#ac864ff8886123039c7d2d3c617f7ef87">TMC26X_READOUT_STALLGUARD</a>&#160;&#160;&#160;1</td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Selects to read out the StallGuard value of the motor. </p>
<dl class="see"><dt><b>See also:</b></dt><dd>readStatus() </dd></dl>
<p>Definition at line <a class="el" href="_t_m_c26_x_stepper_8h_source.html#l00059">59</a> of file <a class="el" href="_t_m_c26_x_stepper_8h_source.html">TMC26XStepper.h</a>.</p>
</div>
</div>
</div><!-- contents -->
<hr class="footer"/><address class="footer"><small>
Generated on Mon Nov 19 2012 20:26:21 for Trinamic TMC26X Stepper Driver for Arduino by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.7.6.1
</small></address>
</body>
</html>

View file

@ -0,0 +1,256 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<title>Trinamic TMC26X Stepper Driver for Arduino: TMC26XStepper.h Source File</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td style="padding-left: 0.5em;">
<div id="projectname">Trinamic TMC26X Stepper Driver for Arduino
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- Generated by Doxygen 1.7.6.1 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li class="current"><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li><a href="files.html"><span>File&#160;List</span></a></li>
<li><a href="globals.html"><span>File&#160;Members</span></a></li>
</ul>
</div>
</div>
<div class="header">
<div class="headertitle">
<div class="title">TMC26XStepper.h</div> </div>
</div><!--header-->
<div class="contents">
<a href="_t_m_c26_x_stepper_8h.html">Go to the documentation of this file.</a><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">/*</span>
<a name="l00002"></a>00002 <span class="comment"> TMC26XStepper.cpp - - TMC26X Stepper library for Wiring/Arduino - Version 0.1</span>
<a name="l00003"></a>00003 <span class="comment"> </span>
<a name="l00004"></a>00004 <span class="comment"> based on the stepper library by Tom Igoe, et. al.</span>
<a name="l00005"></a>00005 <span class="comment"></span>
<a name="l00006"></a>00006 <span class="comment"> Copyright (c) 2011, Interactive Matter, Marcus Nowotny</span>
<a name="l00007"></a>00007 <span class="comment"> </span>
<a name="l00008"></a>00008 <span class="comment"> Permission is hereby granted, free of charge, to any person obtaining a copy</span>
<a name="l00009"></a>00009 <span class="comment"> of this software and associated documentation files (the &quot;Software&quot;), to deal</span>
<a name="l00010"></a>00010 <span class="comment"> in the Software without restriction, including without limitation the rights</span>
<a name="l00011"></a>00011 <span class="comment"> to use, copy, modify, merge, publish, distribute, sublicense, and/or sell</span>
<a name="l00012"></a>00012 <span class="comment"> copies of the Software, and to permit persons to whom the Software is</span>
<a name="l00013"></a>00013 <span class="comment"> furnished to do so, subject to the following conditions:</span>
<a name="l00014"></a>00014 <span class="comment"> </span>
<a name="l00015"></a>00015 <span class="comment"> The above copyright notice and this permission notice shall be included in</span>
<a name="l00016"></a>00016 <span class="comment"> all copies or substantial portions of the Software.</span>
<a name="l00017"></a>00017 <span class="comment"> </span>
<a name="l00018"></a>00018 <span class="comment"> THE SOFTWARE IS PROVIDED &quot;AS IS&quot;, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR</span>
<a name="l00019"></a>00019 <span class="comment"> IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,</span>
<a name="l00020"></a>00020 <span class="comment"> FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE</span>
<a name="l00021"></a>00021 <span class="comment"> AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER</span>
<a name="l00022"></a>00022 <span class="comment"> LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,</span>
<a name="l00023"></a>00023 <span class="comment"> OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN</span>
<a name="l00024"></a>00024 <span class="comment"> THE SOFTWARE.</span>
<a name="l00025"></a>00025 <span class="comment"></span>
<a name="l00026"></a>00026 <span class="comment"> */</span>
<a name="l00027"></a>00027
<a name="l00028"></a>00028
<a name="l00029"></a>00029 <span class="comment">// ensure this library description is only included once</span>
<a name="l00030"></a>00030 <span class="preprocessor">#ifndef TMC26XStepper_h</span>
<a name="l00031"></a>00031 <span class="preprocessor"></span><span class="preprocessor">#define TMC26XStepper_h</span>
<a name="l00032"></a>00032 <span class="preprocessor"></span>
<a name="l00034"></a>00034
<a name="l00039"></a><a class="code" href="_t_m_c26_x_stepper_8h.html#add42eee34f674f92c19bcd5266d2445f">00039</a> <span class="preprocessor">#define TMC26X_OVERTEMPERATURE_PREWARING 1</span>
<a name="l00040"></a>00040 <span class="preprocessor"></span>
<a name="l00041"></a>00041
<a name="l00047"></a><a class="code" href="_t_m_c26_x_stepper_8h.html#adae814ce848677abd87758c7ac79a436">00047</a> <span class="preprocessor">#define TMC26X_OVERTEMPERATURE_SHUTDOWN 2</span>
<a name="l00048"></a>00048 <span class="preprocessor"></span>
<a name="l00049"></a>00049 <span class="comment">//which values can be read out</span>
<a name="l00054"></a><a class="code" href="_t_m_c26_x_stepper_8h.html#aff05d4a47ef8821322ccc2a20785fbee">00054</a> <span class="comment"></span><span class="preprocessor">#define TMC26X_READOUT_POSITION 0</span>
<a name="l00055"></a>00055 <span class="preprocessor"></span>
<a name="l00059"></a><a class="code" href="_t_m_c26_x_stepper_8h.html#ac864ff8886123039c7d2d3c617f7ef87">00059</a> <span class="preprocessor">#define TMC26X_READOUT_STALLGUARD 1</span>
<a name="l00060"></a>00060 <span class="preprocessor"></span>
<a name="l00064"></a><a class="code" href="_t_m_c26_x_stepper_8h.html#a01760ad15e3846536526a990efe47094">00064</a> <span class="preprocessor">#define TMC26X_READOUT_CURRENT 3</span>
<a name="l00065"></a>00065 <span class="preprocessor"></span>
<a name="l00070"></a><a class="code" href="_t_m_c26_x_stepper_8h.html#a28b1774bd4aa854fb5e4b6dc7db96ecb">00070</a> <span class="preprocessor">#define COOL_STEP_HALF_CS_LIMIT 0</span>
<a name="l00071"></a>00071 <span class="preprocessor"></span>
<a name="l00075"></a><a class="code" href="_t_m_c26_x_stepper_8h.html#a1a4db5eafd0a9247677153cb4c8b7d54">00075</a> <span class="preprocessor">#define COOL_STEP_QUARTDER_CS_LIMIT 1</span>
<a name="l00076"></a>00076 <span class="preprocessor"></span>
<a name="l00101"></a><a class="code" href="class_t_m_c26_x_stepper.html">00101</a> <span class="keyword">class </span><a class="code" href="class_t_m_c26_x_stepper.html" title="Class representing a TMC26X stepper driver.">TMC26XStepper</a> {
<a name="l00102"></a>00102 <span class="keyword">public</span>:
<a name="l00124"></a>00124 <a class="code" href="class_t_m_c26_x_stepper.html#a3ef40763b8b8ab2b6ed4978c0647906c" title="creates a new represenatation of a stepper motor connected to a TMC26X stepper driver">TMC26XStepper</a>(<span class="keywordtype">int</span> number_of_steps, <span class="keywordtype">int</span> cs_pin, <span class="keywordtype">int</span> dir_pin, <span class="keywordtype">int</span> step_pin, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> current, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> resistor=150);
<a name="l00125"></a>00125
<a name="l00133"></a>00133 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#aad1ed82b3e05940bde5a6c7ed3d3e8f7" title="configures and starts the TMC26X stepper driver. Before you called this function the stepper driver i...">start</a>();
<a name="l00134"></a>00134
<a name="l00145"></a>00145 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#af968e70a13068f1e71ac0fa6865630c5" title="resets the stepper in unconfigured mode.">un_start</a>();
<a name="l00146"></a>00146
<a name="l00147"></a>00147
<a name="l00152"></a>00152 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#a9478f43090995c8d5cdb4d4e8c07cdbd" title="Sets the rotation speed in revolutions per minute.">setSpeed</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> whatSpeed);
<a name="l00153"></a>00153
<a name="l00158"></a>00158 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="class_t_m_c26_x_stepper.html#aa564f5cc0218d30ef897c2830c768c29" title="reads out the currently selected speed in revolutions per minute.">getSpeed</a>(<span class="keywordtype">void</span>);
<a name="l00159"></a>00159
<a name="l00168"></a>00168 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#a21041579c7f9284567ee2e2a55a3afd0" title="Set the number of microsteps in 2^i values (rounded) up to 256.">setMicrosteps</a>(<span class="keywordtype">int</span> number_of_steps);
<a name="l00169"></a>00169
<a name="l00178"></a>00178 <span class="keywordtype">int</span> <a class="code" href="class_t_m_c26_x_stepper.html#a5808551ced98b79c09bbb4bf47ecfec3" title="returns the effective current number of microsteps selected.">getMicrosteps</a>(<span class="keywordtype">void</span>);
<a name="l00179"></a>00179
<a name="l00195"></a>00195 <span class="keywordtype">char</span> <a class="code" href="class_t_m_c26_x_stepper.html#ac073a742496885f1f60751f9fb9c395d" title="Initiate a movement for the given number of steps. Positive numbers move in one, negative numbers in ...">step</a>(<span class="keywordtype">int</span> number_of_steps);
<a name="l00196"></a>00196
<a name="l00215"></a>00215 <span class="keywordtype">char</span> <a class="code" href="class_t_m_c26_x_stepper.html#aed5d81f1549615529c723600a68ba415" title="Central movement method, must be called as often as possible in the lopp function and is very fast...">move</a>(<span class="keywordtype">void</span>);
<a name="l00216"></a>00216
<a name="l00224"></a>00224 <span class="keywordtype">char</span> <a class="code" href="class_t_m_c26_x_stepper.html#a880d602be8414b7b965287c1790cd50e" title="checks if the motor still has to move to fulfill the last movement command.">isMoving</a>(<span class="keywordtype">void</span>);
<a name="l00225"></a>00225
<a name="l00230"></a>00230 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="class_t_m_c26_x_stepper.html#aa6c3211f85301ca0fb2e7b73cb8142a7" title="Get the number of steps left in the current movement.">getStepsLeft</a>(<span class="keywordtype">void</span>);
<a name="l00231"></a>00231
<a name="l00238"></a>00238 <span class="keywordtype">char</span> <a class="code" href="class_t_m_c26_x_stepper.html#a6315c18eadbc6bf4f3d81a6f80296123" title="Stops the motor regardless if it moves or not.">stop</a>(<span class="keywordtype">void</span>);
<a name="l00239"></a>00239
<a name="l00264"></a>00264 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#ac2d8a2bbae2aba3ed7c98e3ff1a06649" title="Sets and configure the classical Constant Off Timer Chopper.">setConstantOffTimeChopper</a>(<span class="keywordtype">char</span> constant_off_time, <span class="keywordtype">char</span> blank_time, <span class="keywordtype">char</span> fast_decay_time_setting, <span class="keywordtype">char</span> sine_wave_offset, <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> use_current_comparator);
<a name="l00265"></a>00265
<a name="l00286"></a>00286 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#aa152bb7ddb72a2bc8465553a39232df2" title="Sets and configures with spread cycle chopper.">setSpreadCycleChopper</a>(<span class="keywordtype">char</span> constant_off_time, <span class="keywordtype">char</span> blank_time, <span class="keywordtype">char</span> hysteresis_start, <span class="keywordtype">char</span> hysteresis_end, <span class="keywordtype">char</span> hysteresis_decrement);
<a name="l00287"></a>00287
<a name="l00303"></a>00303 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#a7ffd602cf4bf385847cba034417d5f0a" title="Use random off time for noise reduction (0 for off, -1 for on).">setRandomOffTime</a>(<span class="keywordtype">char</span> value);
<a name="l00304"></a>00304
<a name="l00312"></a>00312 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#aaa35fac83417c16b3a941fa168e4a4d2" title="set the maximum motor current in mA (1000 is 1 Amp) Keep in mind this is the maximum peak Current...">setCurrent</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> current);
<a name="l00313"></a>00313
<a name="l00320"></a>00320 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="class_t_m_c26_x_stepper.html#a0c544e23efe3e4a912aacf57de84b71f" title="readout the motor maximum current in mA (1000 is an Amp) This is the maximum current. to get the current current - which may be affected by CoolStep us getCurrentCurrent()">getCurrent</a>(<span class="keywordtype">void</span>);
<a name="l00321"></a>00321
<a name="l00337"></a>00337 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#af1a5abc23757860baf8ff421689a425a" title="set the StallGuard threshold in order to get sensible StallGuard readings.">setStallGuardThreshold</a>(<span class="keywordtype">char</span> stall_guard_threshold, <span class="keywordtype">char</span> stall_guard_filter_enabled);
<a name="l00338"></a>00338
<a name="l00343"></a>00343 <span class="keywordtype">char</span> <a class="code" href="class_t_m_c26_x_stepper.html#a056661f444725c3ae15696d1e8d91def" title="reads out the StallGuard threshold">getStallGuardThreshold</a>(<span class="keywordtype">void</span>);
<a name="l00344"></a>00344
<a name="l00349"></a>00349 <span class="keywordtype">char</span> <a class="code" href="class_t_m_c26_x_stepper.html#a47e3443e3e786314c1099b8f14a91b8a" title="returns the current setting of the StallGuard filter">getStallGuardFilter</a>(<span class="keywordtype">void</span>);
<a name="l00350"></a>00350
<a name="l00368"></a>00368 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#a381fbcce7c586ca2f1da8f9e704df14e" title="This method configures the CoolStep smart energy operation. You must have a proper StallGuard configu...">setCoolStepConfiguration</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> lower_SG_threshold, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> SG_hysteresis, <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> current_decrement_step_size,
<a name="l00369"></a>00369 <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> current_increment_step_size, <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> lower_current_limit);
<a name="l00370"></a>00370
<a name="l00376"></a>00376 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#a15bf0ed5a166a5d9a41f90f3ccbc6157" title="enables or disables the CoolStep smart energy operation feature. It must be configured before enablin...">setCoolStepEnabled</a>(<span class="keywordtype">boolean</span> enabled);
<a name="l00377"></a>00377
<a name="l00378"></a>00378
<a name="l00383"></a>00383 <span class="keywordtype">boolean</span> <a class="code" href="class_t_m_c26_x_stepper.html#a6de2306b6d8dc1fa2e50fccb66d8e66d" title="check if the CoolStep feature is enabled">isCoolStepEnabled</a>();
<a name="l00384"></a>00384
<a name="l00389"></a>00389 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="class_t_m_c26_x_stepper.html#aa7469949deaa39a58038b3ddef532bc8" title="returns the lower StallGuard threshold for the CoolStep operation">getCoolStepLowerSgThreshold</a>();
<a name="l00390"></a>00390
<a name="l00395"></a>00395 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="class_t_m_c26_x_stepper.html#ac61298fd658773c28823d33ab04e970f" title="returns the upper StallGuard threshold for the CoolStep operation">getCoolStepUpperSgThreshold</a>();
<a name="l00396"></a>00396
<a name="l00401"></a>00401 <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> <a class="code" href="class_t_m_c26_x_stepper.html#aad44ee5ae73bf8e69af05674a304ba46" title="returns the number of StallGuard readings befor CoolStep adjusts the motor current.">getCoolStepNumberOfSGReadings</a>();
<a name="l00402"></a>00402
<a name="l00407"></a>00407 <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> <a class="code" href="class_t_m_c26_x_stepper.html#ababe688a15f087d23d4ff2094fcee883" title="returns the increment steps for the current for the CoolStep operation">getCoolStepCurrentIncrementSize</a>();
<a name="l00408"></a>00408
<a name="l00414"></a>00414 <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> <a class="code" href="class_t_m_c26_x_stepper.html#a0c7e8541abc120a3910e35c6fbf2167c" title="returns the absolut minium current for the CoolStep operation">getCoolStepLowerCurrentLimit</a>();
<a name="l00415"></a>00415
<a name="l00422"></a>00422 <span class="keywordtype">int</span> <a class="code" href="class_t_m_c26_x_stepper.html#a1019f6f889acfd3176eecd60a0a20125" title="Get the current microstep position for phase A.">getMotorPosition</a>(<span class="keywordtype">void</span>);
<a name="l00423"></a>00423
<a name="l00430"></a>00430 <span class="keywordtype">int</span> <a class="code" href="class_t_m_c26_x_stepper.html#aed570ce3eea640e087b046333015de1e" title="Reads the current StallGuard value.">getCurrentStallGuardReading</a>(<span class="keywordtype">void</span>);
<a name="l00431"></a>00431
<a name="l00437"></a>00437 <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> <a class="code" href="class_t_m_c26_x_stepper.html#a1a939fb495d747c2c11be99a740371e1" title="Reads the current current setting value as fraction of the maximum current Returns values between 0 a...">getCurrentCSReading</a>(<span class="keywordtype">void</span>);
<a name="l00438"></a>00438
<a name="l00439"></a>00439
<a name="l00444"></a>00444 <span class="keywordtype">boolean</span> <a class="code" href="class_t_m_c26_x_stepper.html#ad435db189ebb101fb2de90a484f33905" title="a convenience method to determine if the current scaling uses 0.31V or 0.165V as reference.">isCurrentScalingHalfed</a>();
<a name="l00445"></a>00445
<a name="l00453"></a>00453 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="class_t_m_c26_x_stepper.html#aa00741168a7def0a7a9d2f2c9d3b99d7" title="Reads the current current setting value and recalculates the absolute current in mA (1A would be 1000...">getCurrentCurrent</a>(<span class="keywordtype">void</span>);
<a name="l00454"></a>00454
<a name="l00463"></a>00463 <span class="keywordtype">boolean</span> <a class="code" href="class_t_m_c26_x_stepper.html#aea4c6e1fac909116c6b55f902d6cff41" title="checks if there is a StallGuard warning in the last status">isStallGuardOverThreshold</a>(<span class="keywordtype">void</span>);
<a name="l00464"></a>00464
<a name="l00471"></a>00471 <span class="keywordtype">char</span> <a class="code" href="class_t_m_c26_x_stepper.html#a7662c2fbc03d1f5a7da5cabcc153b2d7" title="Return over temperature status of the last status readout return 0 is everything is OK...">getOverTemperature</a>(<span class="keywordtype">void</span>);
<a name="l00472"></a>00472
<a name="l00480"></a>00480 <span class="keywordtype">boolean</span> <a class="code" href="class_t_m_c26_x_stepper.html#ad329fa4693d3139dea241ebe3d0f33cf" title="Is motor channel A shorted to ground detected in the last status readout.">isShortToGroundA</a>(<span class="keywordtype">void</span>);
<a name="l00481"></a>00481
<a name="l00488"></a>00488 <span class="keywordtype">boolean</span> <a class="code" href="class_t_m_c26_x_stepper.html#a0ccb54d40cce0d802aa56ff6261f9f3b" title="Is motor channel B shorted to ground detected in the last status readout.">isShortToGroundB</a>(<span class="keywordtype">void</span>);
<a name="l00495"></a>00495 <span class="keywordtype">boolean</span> <a class="code" href="class_t_m_c26_x_stepper.html#af97b2ab9d1ba36765ac6f17cf25ec45c" title="iIs motor channel A connected according to the last statu readout.">isOpenLoadA</a>(<span class="keywordtype">void</span>);
<a name="l00496"></a>00496
<a name="l00503"></a>00503 <span class="keywordtype">boolean</span> <a class="code" href="class_t_m_c26_x_stepper.html#a303590124f5ac6d6a06d0ec60d0b5303" title="iIs motor channel A connected according to the last statu readout.">isOpenLoadB</a>(<span class="keywordtype">void</span>);
<a name="l00504"></a>00504
<a name="l00511"></a>00511 <span class="keywordtype">boolean</span> <a class="code" href="class_t_m_c26_x_stepper.html#ab26602f360a4fb6ec6d262011675b2b0" title="Is chopper inactive since 2^20 clock cycles - defaults to ~0,08s.">isStandStill</a>(<span class="keywordtype">void</span>);
<a name="l00512"></a>00512
<a name="l00524"></a>00524 <span class="keywordtype">boolean</span> <a class="code" href="class_t_m_c26_x_stepper.html#afdeded501ec2cabeffde33d31b6573f7" title="checks if there is a StallGuard warning in the last status">isStallGuardReached</a>(<span class="keywordtype">void</span>);
<a name="l00525"></a>00525
<a name="l00530"></a>00530 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#a4472cd86ad5b65dec5ec45ce69158305" title="enables or disables the motor driver bridges. If disabled the motor can run freely. If enabled not.">setEnabled</a>(<span class="keywordtype">boolean</span> enabled);
<a name="l00531"></a>00531
<a name="l00537"></a>00537 <span class="keywordtype">boolean</span> <a class="code" href="class_t_m_c26_x_stepper.html#a15796c0cbdeab23a343c3f25327283b6" title="checks if the output bridges are enabled. If the bridges are not enabled the motor can run freely...">isEnabled</a>();
<a name="l00538"></a>00538
<a name="l00548"></a>00548 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#af95a824bfdf49ef979b5354798e52967" title="Manually read out the status register This function sends a byte to the motor driver in order to get ...">readStatus</a>(<span class="keywordtype">char</span> read_value);
<a name="l00549"></a>00549
<a name="l00554"></a>00554 <span class="keywordtype">int</span> <a class="code" href="class_t_m_c26_x_stepper.html#ae1db5ec2ec9bfbfaea83c659e006692e" title="Returns the current sense resistor value in milliohm. The default value of ,15 Ohm will return 150...">getResistor</a>();
<a name="l00555"></a>00555
<a name="l00560"></a>00560 <span class="keywordtype">void</span> <a class="code" href="class_t_m_c26_x_stepper.html#ad5e5b1bf5a46d02577dd548083877ec3" title="Prints out all the information that can be found in the last status read out - it does not force a st...">debugLastStatus</a>(<span class="keywordtype">void</span>);
<a name="l00565"></a>00565 <span class="keywordtype">int</span> <a class="code" href="class_t_m_c26_x_stepper.html#ab040d9df1e85d6fb0c105205a36b0215" title="library version">version</a>(<span class="keywordtype">void</span>);
<a name="l00566"></a>00566
<a name="l00567"></a>00567 <span class="keyword">private</span>:
<a name="l00568"></a>00568 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> steps_left; <span class="comment">//the steps the motor has to do to complete the movement</span>
<a name="l00569"></a>00569 <span class="keywordtype">int</span> direction; <span class="comment">// Direction of rotation</span>
<a name="l00570"></a>00570 <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> step_delay; <span class="comment">// delay between steps, in ms, based on speed</span>
<a name="l00571"></a>00571 <span class="keywordtype">int</span> number_of_steps; <span class="comment">// total number of steps this motor can take</span>
<a name="l00572"></a>00572 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> speed; <span class="comment">// we need to store the current speed in order to change the speed after changing microstepping</span>
<a name="l00573"></a>00573 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> resistor; <span class="comment">//current sense resitor value in milliohm</span>
<a name="l00574"></a>00574
<a name="l00575"></a>00575 <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> last_step_time; <span class="comment">// time stamp in ms of when the last step was taken</span>
<a name="l00576"></a>00576 <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> next_step_time; <span class="comment">// time stamp in ms of when the last step was taken</span>
<a name="l00577"></a>00577
<a name="l00578"></a>00578 <span class="comment">//driver control register copies to easily set &amp; modify the registers</span>
<a name="l00579"></a>00579 <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> driver_control_register_value;
<a name="l00580"></a>00580 <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> chopper_config_register;
<a name="l00581"></a>00581 <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> cool_step_register_value;
<a name="l00582"></a>00582 <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> stall_guard2_current_register_value;
<a name="l00583"></a>00583 <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> driver_configuration_register_value;
<a name="l00584"></a>00584 <span class="comment">//the driver status result</span>
<a name="l00585"></a>00585 <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> driver_status_result;
<a name="l00586"></a>00586
<a name="l00587"></a>00587 <span class="comment">//helper routione to get the top 10 bit of the readout</span>
<a name="l00588"></a>00588 <span class="keyword">inline</span> <span class="keywordtype">int</span> getReadoutValue();
<a name="l00589"></a>00589
<a name="l00590"></a>00590 <span class="comment">//the pins for the stepper driver</span>
<a name="l00591"></a>00591 <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> cs_pin;
<a name="l00592"></a>00592 <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> step_pin;
<a name="l00593"></a>00593 <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> dir_pin;
<a name="l00594"></a>00594
<a name="l00595"></a>00595 <span class="comment">//status values </span>
<a name="l00596"></a>00596 <span class="keywordtype">boolean</span> started; <span class="comment">//if the stepper has been started yet</span>
<a name="l00597"></a>00597 <span class="keywordtype">int</span> microsteps; <span class="comment">//the current number of micro steps</span>
<a name="l00598"></a>00598 <span class="keywordtype">char</span> constant_off_time; <span class="comment">//we need to remember this value in order to enable and disable the motor</span>
<a name="l00599"></a>00599 <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> cool_step_lower_threshold; <span class="comment">// we need to remember the threshold to enable and disable the CoolStep feature</span>
<a name="l00600"></a>00600 <span class="keywordtype">boolean</span> cool_step_enabled; <span class="comment">//we need to remember this to configure the coolstep if it si enabled</span>
<a name="l00601"></a>00601
<a name="l00602"></a>00602 <span class="comment">//SPI sender</span>
<a name="l00603"></a>00603 <span class="keyword">inline</span> <span class="keywordtype">void</span> send262(<span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> datagram);
<a name="l00604"></a>00604 };
<a name="l00605"></a>00605
<a name="l00606"></a>00606 <span class="preprocessor">#endif</span>
<a name="l00607"></a>00607 <span class="preprocessor"></span>
</pre></div></div><!-- contents -->
<hr class="footer"/><address class="footer"><small>
Generated on Mon Nov 19 2012 20:26:21 for Trinamic TMC26X Stepper Driver for Arduino by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.7.6.1
</small></address>
</body>
</html>

View file

@ -0,0 +1,72 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<title>Trinamic TMC26X Stepper Driver for Arduino: Class List</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td style="padding-left: 0.5em;">
<div id="projectname">Trinamic TMC26X Stepper Driver for Arduino
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- Generated by Doxygen 1.7.6.1 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li class="current"><a href="annotated.html"><span>Class&#160;List</span></a></li>
<li><a href="classes.html"><span>Class&#160;Index</span></a></li>
<li><a href="functions.html"><span>Class&#160;Members</span></a></li>
</ul>
</div>
</div>
<div class="header">
<div class="headertitle">
<div class="title">Class List</div> </div>
</div><!--header-->
<div class="contents">
<div class="textblock">Here are the classes, structs, unions and interfaces with brief descriptions:</div><table>
<tr><td class="indexkey"><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td class="indexvalue">Class representing a TMC26X stepper driver </td></tr>
</table>
</div><!-- contents -->
<hr class="footer"/><address class="footer"><small>
Generated on Mon Nov 19 2012 20:26:21 for Trinamic TMC26X Stepper Driver for Arduino by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.7.6.1
</small></address>
</body>
</html>

Binary file not shown.

After

Width:  |  Height:  |  Size: 677 B

View file

@ -0,0 +1,117 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<title>Trinamic TMC26X Stepper Driver for Arduino: Member List</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td style="padding-left: 0.5em;">
<div id="projectname">Trinamic TMC26X Stepper Driver for Arduino
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- Generated by Doxygen 1.7.6.1 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li><a href="annotated.html"><span>Class&#160;List</span></a></li>
<li><a href="classes.html"><span>Class&#160;Index</span></a></li>
<li><a href="functions.html"><span>Class&#160;Members</span></a></li>
</ul>
</div>
</div>
<div class="header">
<div class="headertitle">
<div class="title">TMC26XStepper Member List</div> </div>
</div><!--header-->
<div class="contents">
This is the complete list of members for <a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a>, including all inherited members.<table>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#ad5e5b1bf5a46d02577dd548083877ec3">debugLastStatus</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#ababe688a15f087d23d4ff2094fcee883">getCoolStepCurrentIncrementSize</a>()</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a0c7e8541abc120a3910e35c6fbf2167c">getCoolStepLowerCurrentLimit</a>()</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#aa7469949deaa39a58038b3ddef532bc8">getCoolStepLowerSgThreshold</a>()</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#aad44ee5ae73bf8e69af05674a304ba46">getCoolStepNumberOfSGReadings</a>()</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#ac61298fd658773c28823d33ab04e970f">getCoolStepUpperSgThreshold</a>()</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a0c544e23efe3e4a912aacf57de84b71f">getCurrent</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a1a939fb495d747c2c11be99a740371e1">getCurrentCSReading</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#aa00741168a7def0a7a9d2f2c9d3b99d7">getCurrentCurrent</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#aed570ce3eea640e087b046333015de1e">getCurrentStallGuardReading</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a5808551ced98b79c09bbb4bf47ecfec3">getMicrosteps</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a1019f6f889acfd3176eecd60a0a20125">getMotorPosition</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a7662c2fbc03d1f5a7da5cabcc153b2d7">getOverTemperature</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#ae1db5ec2ec9bfbfaea83c659e006692e">getResistor</a>()</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#aa564f5cc0218d30ef897c2830c768c29">getSpeed</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a47e3443e3e786314c1099b8f14a91b8a">getStallGuardFilter</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a056661f444725c3ae15696d1e8d91def">getStallGuardThreshold</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#aa6c3211f85301ca0fb2e7b73cb8142a7">getStepsLeft</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a6de2306b6d8dc1fa2e50fccb66d8e66d">isCoolStepEnabled</a>()</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#ad435db189ebb101fb2de90a484f33905">isCurrentScalingHalfed</a>()</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a15796c0cbdeab23a343c3f25327283b6">isEnabled</a>()</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a880d602be8414b7b965287c1790cd50e">isMoving</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#af97b2ab9d1ba36765ac6f17cf25ec45c">isOpenLoadA</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a303590124f5ac6d6a06d0ec60d0b5303">isOpenLoadB</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#ad329fa4693d3139dea241ebe3d0f33cf">isShortToGroundA</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a0ccb54d40cce0d802aa56ff6261f9f3b">isShortToGroundB</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#aea4c6e1fac909116c6b55f902d6cff41">isStallGuardOverThreshold</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#afdeded501ec2cabeffde33d31b6573f7">isStallGuardReached</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#ab26602f360a4fb6ec6d262011675b2b0">isStandStill</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#aed5d81f1549615529c723600a68ba415">move</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#af95a824bfdf49ef979b5354798e52967">readStatus</a>(char read_value)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#ac2d8a2bbae2aba3ed7c98e3ff1a06649">setConstantOffTimeChopper</a>(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, unsigned char use_current_comparator)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a381fbcce7c586ca2f1da8f9e704df14e">setCoolStepConfiguration</a>(unsigned int lower_SG_threshold, unsigned int SG_hysteresis, unsigned char current_decrement_step_size, unsigned char current_increment_step_size, unsigned char lower_current_limit)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a15bf0ed5a166a5d9a41f90f3ccbc6157">setCoolStepEnabled</a>(boolean enabled)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#aaa35fac83417c16b3a941fa168e4a4d2">setCurrent</a>(unsigned int current)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a4472cd86ad5b65dec5ec45ce69158305">setEnabled</a>(boolean enabled)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a21041579c7f9284567ee2e2a55a3afd0">setMicrosteps</a>(int number_of_steps)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a7ffd602cf4bf385847cba034417d5f0a">setRandomOffTime</a>(char value)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a9478f43090995c8d5cdb4d4e8c07cdbd">setSpeed</a>(unsigned int whatSpeed)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#aa152bb7ddb72a2bc8465553a39232df2">setSpreadCycleChopper</a>(char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#af1a5abc23757860baf8ff421689a425a">setStallGuardThreshold</a>(char stall_guard_threshold, char stall_guard_filter_enabled)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#aad1ed82b3e05940bde5a6c7ed3d3e8f7">start</a>()</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#ac073a742496885f1f60751f9fb9c395d">step</a>(int number_of_steps)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a6315c18eadbc6bf4f3d81a6f80296123">stop</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#a3ef40763b8b8ab2b6ed4978c0647906c">TMC26XStepper</a>(int number_of_steps, int cs_pin, int dir_pin, int step_pin, unsigned int current, unsigned int resistor=150)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#af968e70a13068f1e71ac0fa6865630c5">un_start</a>()</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="class_t_m_c26_x_stepper.html#ab040d9df1e85d6fb0c105205a36b0215">version</a>(void)</td><td><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a></td><td></td></tr>
</table></div><!-- contents -->
<hr class="footer"/><address class="footer"><small>
Generated on Mon Nov 19 2012 20:26:21 for Trinamic TMC26X Stepper Driver for Arduino by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.7.6.1
</small></address>
</body>
</html>

View file

@ -0,0 +1,78 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<title>Trinamic TMC26X Stepper Driver for Arduino: Class Index</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td style="padding-left: 0.5em;">
<div id="projectname">Trinamic TMC26X Stepper Driver for Arduino
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- Generated by Doxygen 1.7.6.1 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li><a href="annotated.html"><span>Class&#160;List</span></a></li>
<li class="current"><a href="classes.html"><span>Class&#160;Index</span></a></li>
<li><a href="functions.html"><span>Class&#160;Members</span></a></li>
</ul>
</div>
</div>
<div class="header">
<div class="headertitle">
<div class="title">Class Index</div> </div>
</div><!--header-->
<div class="contents">
<div class="qindex"><a class="qindex" href="#letter_T">T</a></div>
<table style="margin: 10px; white-space: nowrap;" align="center" width="95%" border="0" cellspacing="0" cellpadding="0">
<tr><td rowspan="2" valign="bottom"><a name="letter_T"></a><table border="0" cellspacing="0" cellpadding="0"><tr><td><div class="ah">&#160;&#160;T&#160;&#160;</div></td></tr></table>
</td><td></td></tr>
<tr><td></td></tr>
<tr><td valign="top"><a class="el" href="class_t_m_c26_x_stepper.html">TMC26XStepper</a>&#160;&#160;&#160;</td><td></td></tr>
<tr><td></td><td></td></tr>
</table>
<div class="qindex"><a class="qindex" href="#letter_T">T</a></div>
</div><!-- contents -->
<hr class="footer"/><address class="footer"><small>
Generated on Mon Nov 19 2012 20:26:21 for Trinamic TMC26X Stepper Driver for Arduino by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.7.6.1
</small></address>
</body>
</html>

Binary file not shown.

After

Width:  |  Height:  |  Size: 126 B

View file

@ -0,0 +1,949 @@
/* The standard CSS for doxygen */
body, table, div, p, dl {
font-family: Lucida Grande, Verdana, Geneva, Arial, sans-serif;
font-size: 13px;
line-height: 1.3;
}
/* @group Heading Levels */
h1 {
font-size: 150%;
}
.title {
font-size: 150%;
font-weight: bold;
margin: 10px 2px;
}
h2 {
font-size: 120%;
}
h3 {
font-size: 100%;
}
dt {
font-weight: bold;
}
div.multicol {
-moz-column-gap: 1em;
-webkit-column-gap: 1em;
-moz-column-count: 3;
-webkit-column-count: 3;
}
p.startli, p.startdd, p.starttd {
margin-top: 2px;
}
p.endli {
margin-bottom: 0px;
}
p.enddd {
margin-bottom: 4px;
}
p.endtd {
margin-bottom: 2px;
}
/* @end */
caption {
font-weight: bold;
}
span.legend {
font-size: 70%;
text-align: center;
}
h3.version {
font-size: 90%;
text-align: center;
}
div.qindex, div.navtab{
background-color: #EBEFF6;
border: 1px solid #A3B4D7;
text-align: center;
}
div.qindex, div.navpath {
width: 100%;
line-height: 140%;
}
div.navtab {
margin-right: 15px;
}
/* @group Link Styling */
a {
color: #3D578C;
font-weight: normal;
text-decoration: none;
}
.contents a:visited {
color: #4665A2;
}
a:hover {
text-decoration: underline;
}
a.qindex {
font-weight: bold;
}
a.qindexHL {
font-weight: bold;
background-color: #9CAFD4;
color: #ffffff;
border: 1px double #869DCA;
}
.contents a.qindexHL:visited {
color: #ffffff;
}
a.el {
font-weight: bold;
}
a.elRef {
}
a.code, a.code:visited {
color: #4665A2;
}
a.codeRef, a.codeRef:visited {
color: #4665A2;
}
/* @end */
dl.el {
margin-left: -1cm;
}
.fragment {
font-family: monospace, fixed;
font-size: 105%;
}
pre.fragment {
border: 1px solid #C4CFE5;
background-color: #FBFCFD;
padding: 4px 6px;
margin: 4px 8px 4px 2px;
overflow: auto;
word-wrap: break-word;
font-size: 9pt;
line-height: 125%;
}
div.ah {
background-color: black;
font-weight: bold;
color: #ffffff;
margin-bottom: 3px;
margin-top: 3px;
padding: 0.2em;
border: solid thin #333;
border-radius: 0.5em;
-webkit-border-radius: .5em;
-moz-border-radius: .5em;
box-shadow: 2px 2px 3px #999;
-webkit-box-shadow: 2px 2px 3px #999;
-moz-box-shadow: rgba(0, 0, 0, 0.15) 2px 2px 2px;
background-image: -webkit-gradient(linear, left top, left bottom, from(#eee), to(#000),color-stop(0.3, #444));
background-image: -moz-linear-gradient(center top, #eee 0%, #444 40%, #000);
}
div.groupHeader {
margin-left: 16px;
margin-top: 12px;
font-weight: bold;
}
div.groupText {
margin-left: 16px;
font-style: italic;
}
body {
background-color: white;
color: black;
margin: 0;
}
div.contents {
margin-top: 10px;
margin-left: 8px;
margin-right: 8px;
}
td.indexkey {
background-color: #EBEFF6;
font-weight: bold;
border: 1px solid #C4CFE5;
margin: 2px 0px 2px 0;
padding: 2px 10px;
white-space: nowrap;
vertical-align: top;
}
td.indexvalue {
background-color: #EBEFF6;
border: 1px solid #C4CFE5;
padding: 2px 10px;
margin: 2px 0px;
}
tr.memlist {
background-color: #EEF1F7;
}
p.formulaDsp {
text-align: center;
}
img.formulaDsp {
}
img.formulaInl {
vertical-align: middle;
}
div.center {
text-align: center;
margin-top: 0px;
margin-bottom: 0px;
padding: 0px;
}
div.center img {
border: 0px;
}
address.footer {
text-align: right;
padding-right: 12px;
}
img.footer {
border: 0px;
vertical-align: middle;
}
/* @group Code Colorization */
span.keyword {
color: #008000
}
span.keywordtype {
color: #604020
}
span.keywordflow {
color: #e08000
}
span.comment {
color: #800000
}
span.preprocessor {
color: #806020
}
span.stringliteral {
color: #002080
}
span.charliteral {
color: #008080
}
span.vhdldigit {
color: #ff00ff
}
span.vhdlchar {
color: #000000
}
span.vhdlkeyword {
color: #700070
}
span.vhdllogic {
color: #ff0000
}
/* @end */
/*
.search {
color: #003399;
font-weight: bold;
}
form.search {
margin-bottom: 0px;
margin-top: 0px;
}
input.search {
font-size: 75%;
color: #000080;
font-weight: normal;
background-color: #e8eef2;
}
*/
td.tiny {
font-size: 75%;
}
.dirtab {
padding: 4px;
border-collapse: collapse;
border: 1px solid #A3B4D7;
}
th.dirtab {
background: #EBEFF6;
font-weight: bold;
}
hr {
height: 0px;
border: none;
border-top: 1px solid #4A6AAA;
}
hr.footer {
height: 1px;
}
/* @group Member Descriptions */
table.memberdecls {
border-spacing: 0px;
padding: 0px;
}
.mdescLeft, .mdescRight,
.memItemLeft, .memItemRight,
.memTemplItemLeft, .memTemplItemRight, .memTemplParams {
background-color: #F9FAFC;
border: none;
margin: 4px;
padding: 1px 0 0 8px;
}
.mdescLeft, .mdescRight {
padding: 0px 8px 4px 8px;
color: #555;
}
.memItemLeft, .memItemRight, .memTemplParams {
border-top: 1px solid #C4CFE5;
}
.memItemLeft, .memTemplItemLeft {
white-space: nowrap;
}
.memItemRight {
width: 100%;
}
.memTemplParams {
color: #4665A2;
white-space: nowrap;
}
/* @end */
/* @group Member Details */
/* Styles for detailed member documentation */
.memtemplate {
font-size: 80%;
color: #4665A2;
font-weight: normal;
margin-left: 9px;
}
.memnav {
background-color: #EBEFF6;
border: 1px solid #A3B4D7;
text-align: center;
margin: 2px;
margin-right: 15px;
padding: 2px;
}
.mempage {
width: 100%;
}
.memitem {
padding: 0;
margin-bottom: 10px;
margin-right: 5px;
}
.memname {
white-space: nowrap;
font-weight: bold;
margin-left: 6px;
}
.memproto, dl.reflist dt {
border-top: 1px solid #A8B8D9;
border-left: 1px solid #A8B8D9;
border-right: 1px solid #A8B8D9;
padding: 6px 0px 6px 0px;
color: #253555;
font-weight: bold;
text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9);
/* opera specific markup */
box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15);
border-top-right-radius: 8px;
border-top-left-radius: 8px;
/* firefox specific markup */
-moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px;
-moz-border-radius-topright: 8px;
-moz-border-radius-topleft: 8px;
/* webkit specific markup */
-webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15);
-webkit-border-top-right-radius: 8px;
-webkit-border-top-left-radius: 8px;
background-image:url('nav_f.png');
background-repeat:repeat-x;
background-color: #E2E8F2;
}
.memdoc, dl.reflist dd {
border-bottom: 1px solid #A8B8D9;
border-left: 1px solid #A8B8D9;
border-right: 1px solid #A8B8D9;
padding: 2px 5px;
background-color: #FBFCFD;
border-top-width: 0;
/* opera specific markup */
border-bottom-left-radius: 8px;
border-bottom-right-radius: 8px;
box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15);
/* firefox specific markup */
-moz-border-radius-bottomleft: 8px;
-moz-border-radius-bottomright: 8px;
-moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px;
background-image: -moz-linear-gradient(center top, #FFFFFF 0%, #FFFFFF 60%, #F7F8FB 95%, #EEF1F7);
/* webkit specific markup */
-webkit-border-bottom-left-radius: 8px;
-webkit-border-bottom-right-radius: 8px;
-webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15);
background-image: -webkit-gradient(linear,center top,center bottom,from(#FFFFFF), color-stop(0.6,#FFFFFF), color-stop(0.60,#FFFFFF), color-stop(0.95,#F7F8FB), to(#EEF1F7));
}
dl.reflist dt {
padding: 5px;
}
dl.reflist dd {
margin: 0px 0px 10px 0px;
padding: 5px;
}
.paramkey {
text-align: right;
}
.paramtype {
white-space: nowrap;
}
.paramname {
color: #602020;
white-space: nowrap;
}
.paramname em {
font-style: normal;
}
.params, .retval, .exception, .tparams {
border-spacing: 6px 2px;
}
.params .paramname, .retval .paramname {
font-weight: bold;
vertical-align: top;
}
.params .paramtype {
font-style: italic;
vertical-align: top;
}
.params .paramdir {
font-family: "courier new",courier,monospace;
vertical-align: top;
}
/* @end */
/* @group Directory (tree) */
/* for the tree view */
.ftvtree {
font-family: sans-serif;
margin: 0px;
}
/* these are for tree view when used as main index */
.directory {
font-size: 9pt;
font-weight: bold;
margin: 5px;
}
.directory h3 {
margin: 0px;
margin-top: 1em;
font-size: 11pt;
}
/*
The following two styles can be used to replace the root node title
with an image of your choice. Simply uncomment the next two styles,
specify the name of your image and be sure to set 'height' to the
proper pixel height of your image.
*/
/*
.directory h3.swap {
height: 61px;
background-repeat: no-repeat;
background-image: url("yourimage.gif");
}
.directory h3.swap span {
display: none;
}
*/
.directory > h3 {
margin-top: 0;
}
.directory p {
margin: 0px;
white-space: nowrap;
}
.directory div {
display: none;
margin: 0px;
}
.directory img {
vertical-align: -30%;
}
/* these are for tree view when not used as main index */
.directory-alt {
font-size: 100%;
font-weight: bold;
}
.directory-alt h3 {
margin: 0px;
margin-top: 1em;
font-size: 11pt;
}
.directory-alt > h3 {
margin-top: 0;
}
.directory-alt p {
margin: 0px;
white-space: nowrap;
}
.directory-alt div {
display: none;
margin: 0px;
}
.directory-alt img {
vertical-align: -30%;
}
/* @end */
div.dynheader {
margin-top: 8px;
}
address {
font-style: normal;
color: #2A3D61;
}
table.doxtable {
border-collapse:collapse;
}
table.doxtable td, table.doxtable th {
border: 1px solid #2D4068;
padding: 3px 7px 2px;
}
table.doxtable th {
background-color: #374F7F;
color: #FFFFFF;
font-size: 110%;
padding-bottom: 4px;
padding-top: 5px;
text-align:left;
}
table.fieldtable {
width: 100%;
margin-bottom: 10px;
border: 1px solid #A8B8D9;
border-spacing: 0px;
-moz-border-radius: 4px;
-webkit-border-radius: 4px;
border-radius: 4px;
-moz-box-shadow: rgba(0, 0, 0, 0.15) 2px 2px 2px;
-webkit-box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15);
box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15);
}
.fieldtable td, .fieldtable th {
padding: 3px 7px 2px;
}
.fieldtable td.fieldtype, .fieldtable td.fieldname {
white-space: nowrap;
border-right: 1px solid #A8B8D9;
border-bottom: 1px solid #A8B8D9;
vertical-align: top;
}
.fieldtable td.fielddoc {
border-bottom: 1px solid #A8B8D9;
width: 100%;
}
.fieldtable tr:last-child td {
border-bottom: none;
}
.fieldtable th {
background-image:url('nav_f.png');
background-repeat:repeat-x;
background-color: #E2E8F2;
font-size: 90%;
color: #253555;
padding-bottom: 4px;
padding-top: 5px;
text-align:left;
-moz-border-radius-topleft: 4px;
-moz-border-radius-topright: 4px;
-webkit-border-top-left-radius: 4px;
-webkit-border-top-right-radius: 4px;
border-top-left-radius: 4px;
border-top-right-radius: 4px;
border-bottom: 1px solid #A8B8D9;
}
.tabsearch {
top: 0px;
left: 10px;
height: 36px;
background-image: url('tab_b.png');
z-index: 101;
overflow: hidden;
font-size: 13px;
}
.navpath ul
{
font-size: 11px;
background-image:url('tab_b.png');
background-repeat:repeat-x;
height:30px;
line-height:30px;
color:#8AA0CC;
border:solid 1px #C2CDE4;
overflow:hidden;
margin:0px;
padding:0px;
}
.navpath li
{
list-style-type:none;
float:left;
padding-left:10px;
padding-right:15px;
background-image:url('bc_s.png');
background-repeat:no-repeat;
background-position:right;
color:#364D7C;
}
.navpath li.navelem a
{
height:32px;
display:block;
text-decoration: none;
outline: none;
}
.navpath li.navelem a:hover
{
color:#6884BD;
}
.navpath li.footer
{
list-style-type:none;
float:right;
padding-left:10px;
padding-right:15px;
background-image:none;
background-repeat:no-repeat;
background-position:right;
color:#364D7C;
font-size: 8pt;
}
div.summary
{
float: right;
font-size: 8pt;
padding-right: 5px;
width: 50%;
text-align: right;
}
div.summary a
{
white-space: nowrap;
}
div.ingroups
{
margin-left: 5px;
font-size: 8pt;
padding-left: 5px;
width: 50%;
text-align: left;
}
div.ingroups a
{
white-space: nowrap;
}
div.header
{
background-image:url('nav_h.png');
background-repeat:repeat-x;
background-color: #F9FAFC;
margin: 0px;
border-bottom: 1px solid #C4CFE5;
}
div.headertitle
{
padding: 5px 5px 5px 7px;
}
dl
{
padding: 0 0 0 10px;
}
dl.note, dl.warning, dl.attention, dl.pre, dl.post, dl.invariant, dl.deprecated, dl.todo, dl.test, dl.bug
{
border-left:4px solid;
padding: 0 0 0 6px;
}
dl.note
{
border-color: #D0C000;
}
dl.warning, dl.attention
{
border-color: #FF0000;
}
dl.pre, dl.post, dl.invariant
{
border-color: #00D000;
}
dl.deprecated
{
border-color: #505050;
}
dl.todo
{
border-color: #00C0E0;
}
dl.test
{
border-color: #3030E0;
}
dl.bug
{
border-color: #C08050;
}
#projectlogo
{
text-align: center;
vertical-align: bottom;
border-collapse: separate;
}
#projectlogo img
{
border: 0px none;
}
#projectname
{
font: 300% Tahoma, Arial,sans-serif;
margin: 0px;
padding: 2px 0px;
}
#projectbrief
{
font: 120% Tahoma, Arial,sans-serif;
margin: 0px;
padding: 0px;
}
#projectnumber
{
font: 50% Tahoma, Arial,sans-serif;
margin: 0px;
padding: 0px;
}
#titlearea
{
padding: 0px;
margin: 0px;
width: 100%;
border-bottom: 1px solid #5373B4;
}
.image
{
text-align: center;
}
.dotgraph
{
text-align: center;
}
.mscgraph
{
text-align: center;
}
.caption
{
font-weight: bold;
}
div.zoom
{
border: 1px solid #90A5CE;
}
dl.citelist {
margin-bottom:50px;
}
dl.citelist dt {
color:#334975;
float:left;
font-weight:bold;
margin-right:10px;
padding:5px;
}
dl.citelist dd {
margin:2px 0;
padding:5px 0;
}
@media print
{
#top { display: none; }
#side-nav { display: none; }
#nav-path { display: none; }
body { overflow:visible; }
h1, h2, h3, h4, h5, h6 { page-break-after: avoid; }
.summary { display: none; }
.memitem { page-break-inside: avoid; }
#doc-content
{
margin-left:0 !important;
height:auto !important;
width:auto !important;
overflow:inherit;
display:inline;
}
pre.fragment
{
overflow: visible;
text-wrap: unrestricted;
white-space: -moz-pre-wrap; /* Moz */
white-space: -pre-wrap; /* Opera 4-6 */
white-space: -o-pre-wrap; /* Opera 7 */
white-space: pre-wrap; /* CSS3 */
word-wrap: break-word; /* IE 5.5+ */
}
}

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.8 KiB

View file

@ -0,0 +1,72 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<title>Trinamic TMC26X Stepper Driver for Arduino: File List</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td style="padding-left: 0.5em;">
<div id="projectname">Trinamic TMC26X Stepper Driver for Arduino
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- Generated by Doxygen 1.7.6.1 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li class="current"><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li class="current"><a href="files.html"><span>File&#160;List</span></a></li>
<li><a href="globals.html"><span>File&#160;Members</span></a></li>
</ul>
</div>
</div>
<div class="header">
<div class="headertitle">
<div class="title">File List</div> </div>
</div><!--header-->
<div class="contents">
<div class="textblock">Here is a list of all files with brief descriptions:</div><table>
<tr><td class="indexkey"><a class="el" href="_t_m_c26_x_stepper_8cpp.html">TMC26XStepper.cpp</a> <a href="_t_m_c26_x_stepper_8cpp_source.html">[code]</a></td><td class="indexvalue"></td></tr>
<tr><td class="indexkey"><a class="el" href="_t_m_c26_x_stepper_8h.html">TMC26XStepper.h</a> <a href="_t_m_c26_x_stepper_8h_source.html">[code]</a></td><td class="indexvalue"></td></tr>
</table>
</div><!-- contents -->
<hr class="footer"/><address class="footer"><small>
Generated on Mon Nov 19 2012 20:26:21 for Trinamic TMC26X Stepper Driver for Arduino by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.7.6.1
</small></address>
</body>
</html>

View file

@ -0,0 +1,261 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<title>Trinamic TMC26X Stepper Driver for Arduino: Class Members</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td style="padding-left: 0.5em;">
<div id="projectname">Trinamic TMC26X Stepper Driver for Arduino
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- Generated by Doxygen 1.7.6.1 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li><a href="annotated.html"><span>Class&#160;List</span></a></li>
<li><a href="classes.html"><span>Class&#160;Index</span></a></li>
<li class="current"><a href="functions.html"><span>Class&#160;Members</span></a></li>
</ul>
</div>
<div id="navrow3" class="tabs2">
<ul class="tablist">
<li class="current"><a href="functions.html"><span>All</span></a></li>
<li><a href="functions_func.html"><span>Functions</span></a></li>
</ul>
</div>
<div id="navrow4" class="tabs3">
<ul class="tablist">
<li><a href="#index_d"><span>d</span></a></li>
<li><a href="#index_g"><span>g</span></a></li>
<li><a href="#index_i"><span>i</span></a></li>
<li><a href="#index_m"><span>m</span></a></li>
<li><a href="#index_r"><span>r</span></a></li>
<li><a href="#index_s"><span>s</span></a></li>
<li><a href="#index_t"><span>t</span></a></li>
<li><a href="#index_u"><span>u</span></a></li>
<li><a href="#index_v"><span>v</span></a></li>
</ul>
</div>
</div>
<div class="contents">
<div class="textblock">Here is a list of all class members with links to the classes they belong to:</div>
<h3><a class="anchor" id="index_d"></a>- d -</h3><ul>
<li>debugLastStatus()
: <a class="el" href="class_t_m_c26_x_stepper.html#ad5e5b1bf5a46d02577dd548083877ec3">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_g"></a>- g -</h3><ul>
<li>getCoolStepCurrentIncrementSize()
: <a class="el" href="class_t_m_c26_x_stepper.html#ababe688a15f087d23d4ff2094fcee883">TMC26XStepper</a>
</li>
<li>getCoolStepLowerCurrentLimit()
: <a class="el" href="class_t_m_c26_x_stepper.html#a0c7e8541abc120a3910e35c6fbf2167c">TMC26XStepper</a>
</li>
<li>getCoolStepLowerSgThreshold()
: <a class="el" href="class_t_m_c26_x_stepper.html#aa7469949deaa39a58038b3ddef532bc8">TMC26XStepper</a>
</li>
<li>getCoolStepNumberOfSGReadings()
: <a class="el" href="class_t_m_c26_x_stepper.html#aad44ee5ae73bf8e69af05674a304ba46">TMC26XStepper</a>
</li>
<li>getCoolStepUpperSgThreshold()
: <a class="el" href="class_t_m_c26_x_stepper.html#ac61298fd658773c28823d33ab04e970f">TMC26XStepper</a>
</li>
<li>getCurrent()
: <a class="el" href="class_t_m_c26_x_stepper.html#a0c544e23efe3e4a912aacf57de84b71f">TMC26XStepper</a>
</li>
<li>getCurrentCSReading()
: <a class="el" href="class_t_m_c26_x_stepper.html#a1a939fb495d747c2c11be99a740371e1">TMC26XStepper</a>
</li>
<li>getCurrentCurrent()
: <a class="el" href="class_t_m_c26_x_stepper.html#aa00741168a7def0a7a9d2f2c9d3b99d7">TMC26XStepper</a>
</li>
<li>getCurrentStallGuardReading()
: <a class="el" href="class_t_m_c26_x_stepper.html#aed570ce3eea640e087b046333015de1e">TMC26XStepper</a>
</li>
<li>getMicrosteps()
: <a class="el" href="class_t_m_c26_x_stepper.html#a5808551ced98b79c09bbb4bf47ecfec3">TMC26XStepper</a>
</li>
<li>getMotorPosition()
: <a class="el" href="class_t_m_c26_x_stepper.html#a1019f6f889acfd3176eecd60a0a20125">TMC26XStepper</a>
</li>
<li>getOverTemperature()
: <a class="el" href="class_t_m_c26_x_stepper.html#a7662c2fbc03d1f5a7da5cabcc153b2d7">TMC26XStepper</a>
</li>
<li>getResistor()
: <a class="el" href="class_t_m_c26_x_stepper.html#ae1db5ec2ec9bfbfaea83c659e006692e">TMC26XStepper</a>
</li>
<li>getSpeed()
: <a class="el" href="class_t_m_c26_x_stepper.html#aa564f5cc0218d30ef897c2830c768c29">TMC26XStepper</a>
</li>
<li>getStallGuardFilter()
: <a class="el" href="class_t_m_c26_x_stepper.html#a47e3443e3e786314c1099b8f14a91b8a">TMC26XStepper</a>
</li>
<li>getStallGuardThreshold()
: <a class="el" href="class_t_m_c26_x_stepper.html#a056661f444725c3ae15696d1e8d91def">TMC26XStepper</a>
</li>
<li>getStepsLeft()
: <a class="el" href="class_t_m_c26_x_stepper.html#aa6c3211f85301ca0fb2e7b73cb8142a7">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_i"></a>- i -</h3><ul>
<li>isCoolStepEnabled()
: <a class="el" href="class_t_m_c26_x_stepper.html#a6de2306b6d8dc1fa2e50fccb66d8e66d">TMC26XStepper</a>
</li>
<li>isCurrentScalingHalfed()
: <a class="el" href="class_t_m_c26_x_stepper.html#ad435db189ebb101fb2de90a484f33905">TMC26XStepper</a>
</li>
<li>isEnabled()
: <a class="el" href="class_t_m_c26_x_stepper.html#a15796c0cbdeab23a343c3f25327283b6">TMC26XStepper</a>
</li>
<li>isMoving()
: <a class="el" href="class_t_m_c26_x_stepper.html#a880d602be8414b7b965287c1790cd50e">TMC26XStepper</a>
</li>
<li>isOpenLoadA()
: <a class="el" href="class_t_m_c26_x_stepper.html#af97b2ab9d1ba36765ac6f17cf25ec45c">TMC26XStepper</a>
</li>
<li>isOpenLoadB()
: <a class="el" href="class_t_m_c26_x_stepper.html#a303590124f5ac6d6a06d0ec60d0b5303">TMC26XStepper</a>
</li>
<li>isShortToGroundA()
: <a class="el" href="class_t_m_c26_x_stepper.html#ad329fa4693d3139dea241ebe3d0f33cf">TMC26XStepper</a>
</li>
<li>isShortToGroundB()
: <a class="el" href="class_t_m_c26_x_stepper.html#a0ccb54d40cce0d802aa56ff6261f9f3b">TMC26XStepper</a>
</li>
<li>isStallGuardOverThreshold()
: <a class="el" href="class_t_m_c26_x_stepper.html#aea4c6e1fac909116c6b55f902d6cff41">TMC26XStepper</a>
</li>
<li>isStallGuardReached()
: <a class="el" href="class_t_m_c26_x_stepper.html#afdeded501ec2cabeffde33d31b6573f7">TMC26XStepper</a>
</li>
<li>isStandStill()
: <a class="el" href="class_t_m_c26_x_stepper.html#ab26602f360a4fb6ec6d262011675b2b0">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_m"></a>- m -</h3><ul>
<li>move()
: <a class="el" href="class_t_m_c26_x_stepper.html#aed5d81f1549615529c723600a68ba415">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_r"></a>- r -</h3><ul>
<li>readStatus()
: <a class="el" href="class_t_m_c26_x_stepper.html#af95a824bfdf49ef979b5354798e52967">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_s"></a>- s -</h3><ul>
<li>setConstantOffTimeChopper()
: <a class="el" href="class_t_m_c26_x_stepper.html#ac2d8a2bbae2aba3ed7c98e3ff1a06649">TMC26XStepper</a>
</li>
<li>setCoolStepConfiguration()
: <a class="el" href="class_t_m_c26_x_stepper.html#a381fbcce7c586ca2f1da8f9e704df14e">TMC26XStepper</a>
</li>
<li>setCoolStepEnabled()
: <a class="el" href="class_t_m_c26_x_stepper.html#a15bf0ed5a166a5d9a41f90f3ccbc6157">TMC26XStepper</a>
</li>
<li>setCurrent()
: <a class="el" href="class_t_m_c26_x_stepper.html#aaa35fac83417c16b3a941fa168e4a4d2">TMC26XStepper</a>
</li>
<li>setEnabled()
: <a class="el" href="class_t_m_c26_x_stepper.html#a4472cd86ad5b65dec5ec45ce69158305">TMC26XStepper</a>
</li>
<li>setMicrosteps()
: <a class="el" href="class_t_m_c26_x_stepper.html#a21041579c7f9284567ee2e2a55a3afd0">TMC26XStepper</a>
</li>
<li>setRandomOffTime()
: <a class="el" href="class_t_m_c26_x_stepper.html#a7ffd602cf4bf385847cba034417d5f0a">TMC26XStepper</a>
</li>
<li>setSpeed()
: <a class="el" href="class_t_m_c26_x_stepper.html#a9478f43090995c8d5cdb4d4e8c07cdbd">TMC26XStepper</a>
</li>
<li>setSpreadCycleChopper()
: <a class="el" href="class_t_m_c26_x_stepper.html#aa152bb7ddb72a2bc8465553a39232df2">TMC26XStepper</a>
</li>
<li>setStallGuardThreshold()
: <a class="el" href="class_t_m_c26_x_stepper.html#af1a5abc23757860baf8ff421689a425a">TMC26XStepper</a>
</li>
<li>start()
: <a class="el" href="class_t_m_c26_x_stepper.html#aad1ed82b3e05940bde5a6c7ed3d3e8f7">TMC26XStepper</a>
</li>
<li>step()
: <a class="el" href="class_t_m_c26_x_stepper.html#ac073a742496885f1f60751f9fb9c395d">TMC26XStepper</a>
</li>
<li>stop()
: <a class="el" href="class_t_m_c26_x_stepper.html#a6315c18eadbc6bf4f3d81a6f80296123">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_t"></a>- t -</h3><ul>
<li>TMC26XStepper()
: <a class="el" href="class_t_m_c26_x_stepper.html#a3ef40763b8b8ab2b6ed4978c0647906c">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_u"></a>- u -</h3><ul>
<li>un_start()
: <a class="el" href="class_t_m_c26_x_stepper.html#af968e70a13068f1e71ac0fa6865630c5">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_v"></a>- v -</h3><ul>
<li>version()
: <a class="el" href="class_t_m_c26_x_stepper.html#ab040d9df1e85d6fb0c105205a36b0215">TMC26XStepper</a>
</li>
</ul>
</div><!-- contents -->
<hr class="footer"/><address class="footer"><small>
Generated on Mon Nov 19 2012 20:26:21 for Trinamic TMC26X Stepper Driver for Arduino by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.7.6.1
</small></address>
</body>
</html>

View file

@ -0,0 +1,261 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<title>Trinamic TMC26X Stepper Driver for Arduino: Class Members - Functions</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td style="padding-left: 0.5em;">
<div id="projectname">Trinamic TMC26X Stepper Driver for Arduino
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- Generated by Doxygen 1.7.6.1 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li><a href="annotated.html"><span>Class&#160;List</span></a></li>
<li><a href="classes.html"><span>Class&#160;Index</span></a></li>
<li class="current"><a href="functions.html"><span>Class&#160;Members</span></a></li>
</ul>
</div>
<div id="navrow3" class="tabs2">
<ul class="tablist">
<li><a href="functions.html"><span>All</span></a></li>
<li class="current"><a href="functions_func.html"><span>Functions</span></a></li>
</ul>
</div>
<div id="navrow4" class="tabs3">
<ul class="tablist">
<li><a href="#index_d"><span>d</span></a></li>
<li><a href="#index_g"><span>g</span></a></li>
<li><a href="#index_i"><span>i</span></a></li>
<li><a href="#index_m"><span>m</span></a></li>
<li><a href="#index_r"><span>r</span></a></li>
<li><a href="#index_s"><span>s</span></a></li>
<li><a href="#index_t"><span>t</span></a></li>
<li><a href="#index_u"><span>u</span></a></li>
<li><a href="#index_v"><span>v</span></a></li>
</ul>
</div>
</div>
<div class="contents">
&#160;
<h3><a class="anchor" id="index_d"></a>- d -</h3><ul>
<li>debugLastStatus()
: <a class="el" href="class_t_m_c26_x_stepper.html#ad5e5b1bf5a46d02577dd548083877ec3">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_g"></a>- g -</h3><ul>
<li>getCoolStepCurrentIncrementSize()
: <a class="el" href="class_t_m_c26_x_stepper.html#ababe688a15f087d23d4ff2094fcee883">TMC26XStepper</a>
</li>
<li>getCoolStepLowerCurrentLimit()
: <a class="el" href="class_t_m_c26_x_stepper.html#a0c7e8541abc120a3910e35c6fbf2167c">TMC26XStepper</a>
</li>
<li>getCoolStepLowerSgThreshold()
: <a class="el" href="class_t_m_c26_x_stepper.html#aa7469949deaa39a58038b3ddef532bc8">TMC26XStepper</a>
</li>
<li>getCoolStepNumberOfSGReadings()
: <a class="el" href="class_t_m_c26_x_stepper.html#aad44ee5ae73bf8e69af05674a304ba46">TMC26XStepper</a>
</li>
<li>getCoolStepUpperSgThreshold()
: <a class="el" href="class_t_m_c26_x_stepper.html#ac61298fd658773c28823d33ab04e970f">TMC26XStepper</a>
</li>
<li>getCurrent()
: <a class="el" href="class_t_m_c26_x_stepper.html#a0c544e23efe3e4a912aacf57de84b71f">TMC26XStepper</a>
</li>
<li>getCurrentCSReading()
: <a class="el" href="class_t_m_c26_x_stepper.html#a1a939fb495d747c2c11be99a740371e1">TMC26XStepper</a>
</li>
<li>getCurrentCurrent()
: <a class="el" href="class_t_m_c26_x_stepper.html#aa00741168a7def0a7a9d2f2c9d3b99d7">TMC26XStepper</a>
</li>
<li>getCurrentStallGuardReading()
: <a class="el" href="class_t_m_c26_x_stepper.html#aed570ce3eea640e087b046333015de1e">TMC26XStepper</a>
</li>
<li>getMicrosteps()
: <a class="el" href="class_t_m_c26_x_stepper.html#a5808551ced98b79c09bbb4bf47ecfec3">TMC26XStepper</a>
</li>
<li>getMotorPosition()
: <a class="el" href="class_t_m_c26_x_stepper.html#a1019f6f889acfd3176eecd60a0a20125">TMC26XStepper</a>
</li>
<li>getOverTemperature()
: <a class="el" href="class_t_m_c26_x_stepper.html#a7662c2fbc03d1f5a7da5cabcc153b2d7">TMC26XStepper</a>
</li>
<li>getResistor()
: <a class="el" href="class_t_m_c26_x_stepper.html#ae1db5ec2ec9bfbfaea83c659e006692e">TMC26XStepper</a>
</li>
<li>getSpeed()
: <a class="el" href="class_t_m_c26_x_stepper.html#aa564f5cc0218d30ef897c2830c768c29">TMC26XStepper</a>
</li>
<li>getStallGuardFilter()
: <a class="el" href="class_t_m_c26_x_stepper.html#a47e3443e3e786314c1099b8f14a91b8a">TMC26XStepper</a>
</li>
<li>getStallGuardThreshold()
: <a class="el" href="class_t_m_c26_x_stepper.html#a056661f444725c3ae15696d1e8d91def">TMC26XStepper</a>
</li>
<li>getStepsLeft()
: <a class="el" href="class_t_m_c26_x_stepper.html#aa6c3211f85301ca0fb2e7b73cb8142a7">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_i"></a>- i -</h3><ul>
<li>isCoolStepEnabled()
: <a class="el" href="class_t_m_c26_x_stepper.html#a6de2306b6d8dc1fa2e50fccb66d8e66d">TMC26XStepper</a>
</li>
<li>isCurrentScalingHalfed()
: <a class="el" href="class_t_m_c26_x_stepper.html#ad435db189ebb101fb2de90a484f33905">TMC26XStepper</a>
</li>
<li>isEnabled()
: <a class="el" href="class_t_m_c26_x_stepper.html#a15796c0cbdeab23a343c3f25327283b6">TMC26XStepper</a>
</li>
<li>isMoving()
: <a class="el" href="class_t_m_c26_x_stepper.html#a880d602be8414b7b965287c1790cd50e">TMC26XStepper</a>
</li>
<li>isOpenLoadA()
: <a class="el" href="class_t_m_c26_x_stepper.html#af97b2ab9d1ba36765ac6f17cf25ec45c">TMC26XStepper</a>
</li>
<li>isOpenLoadB()
: <a class="el" href="class_t_m_c26_x_stepper.html#a303590124f5ac6d6a06d0ec60d0b5303">TMC26XStepper</a>
</li>
<li>isShortToGroundA()
: <a class="el" href="class_t_m_c26_x_stepper.html#ad329fa4693d3139dea241ebe3d0f33cf">TMC26XStepper</a>
</li>
<li>isShortToGroundB()
: <a class="el" href="class_t_m_c26_x_stepper.html#a0ccb54d40cce0d802aa56ff6261f9f3b">TMC26XStepper</a>
</li>
<li>isStallGuardOverThreshold()
: <a class="el" href="class_t_m_c26_x_stepper.html#aea4c6e1fac909116c6b55f902d6cff41">TMC26XStepper</a>
</li>
<li>isStallGuardReached()
: <a class="el" href="class_t_m_c26_x_stepper.html#afdeded501ec2cabeffde33d31b6573f7">TMC26XStepper</a>
</li>
<li>isStandStill()
: <a class="el" href="class_t_m_c26_x_stepper.html#ab26602f360a4fb6ec6d262011675b2b0">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_m"></a>- m -</h3><ul>
<li>move()
: <a class="el" href="class_t_m_c26_x_stepper.html#aed5d81f1549615529c723600a68ba415">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_r"></a>- r -</h3><ul>
<li>readStatus()
: <a class="el" href="class_t_m_c26_x_stepper.html#af95a824bfdf49ef979b5354798e52967">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_s"></a>- s -</h3><ul>
<li>setConstantOffTimeChopper()
: <a class="el" href="class_t_m_c26_x_stepper.html#ac2d8a2bbae2aba3ed7c98e3ff1a06649">TMC26XStepper</a>
</li>
<li>setCoolStepConfiguration()
: <a class="el" href="class_t_m_c26_x_stepper.html#a381fbcce7c586ca2f1da8f9e704df14e">TMC26XStepper</a>
</li>
<li>setCoolStepEnabled()
: <a class="el" href="class_t_m_c26_x_stepper.html#a15bf0ed5a166a5d9a41f90f3ccbc6157">TMC26XStepper</a>
</li>
<li>setCurrent()
: <a class="el" href="class_t_m_c26_x_stepper.html#aaa35fac83417c16b3a941fa168e4a4d2">TMC26XStepper</a>
</li>
<li>setEnabled()
: <a class="el" href="class_t_m_c26_x_stepper.html#a4472cd86ad5b65dec5ec45ce69158305">TMC26XStepper</a>
</li>
<li>setMicrosteps()
: <a class="el" href="class_t_m_c26_x_stepper.html#a21041579c7f9284567ee2e2a55a3afd0">TMC26XStepper</a>
</li>
<li>setRandomOffTime()
: <a class="el" href="class_t_m_c26_x_stepper.html#a7ffd602cf4bf385847cba034417d5f0a">TMC26XStepper</a>
</li>
<li>setSpeed()
: <a class="el" href="class_t_m_c26_x_stepper.html#a9478f43090995c8d5cdb4d4e8c07cdbd">TMC26XStepper</a>
</li>
<li>setSpreadCycleChopper()
: <a class="el" href="class_t_m_c26_x_stepper.html#aa152bb7ddb72a2bc8465553a39232df2">TMC26XStepper</a>
</li>
<li>setStallGuardThreshold()
: <a class="el" href="class_t_m_c26_x_stepper.html#af1a5abc23757860baf8ff421689a425a">TMC26XStepper</a>
</li>
<li>start()
: <a class="el" href="class_t_m_c26_x_stepper.html#aad1ed82b3e05940bde5a6c7ed3d3e8f7">TMC26XStepper</a>
</li>
<li>step()
: <a class="el" href="class_t_m_c26_x_stepper.html#ac073a742496885f1f60751f9fb9c395d">TMC26XStepper</a>
</li>
<li>stop()
: <a class="el" href="class_t_m_c26_x_stepper.html#a6315c18eadbc6bf4f3d81a6f80296123">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_t"></a>- t -</h3><ul>
<li>TMC26XStepper()
: <a class="el" href="class_t_m_c26_x_stepper.html#a3ef40763b8b8ab2b6ed4978c0647906c">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_u"></a>- u -</h3><ul>
<li>un_start()
: <a class="el" href="class_t_m_c26_x_stepper.html#af968e70a13068f1e71ac0fa6865630c5">TMC26XStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_v"></a>- v -</h3><ul>
<li>version()
: <a class="el" href="class_t_m_c26_x_stepper.html#ab040d9df1e85d6fb0c105205a36b0215">TMC26XStepper</a>
</li>
</ul>
</div><!-- contents -->
<hr class="footer"/><address class="footer"><small>
Generated on Mon Nov 19 2012 20:26:21 for Trinamic TMC26X Stepper Driver for Arduino by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.7.6.1
</small></address>
</body>
</html>

View file

@ -0,0 +1,289 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<title>Trinamic TMC26X Stepper Driver for Arduino: File Members</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td style="padding-left: 0.5em;">
<div id="projectname">Trinamic TMC26X Stepper Driver for Arduino
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- Generated by Doxygen 1.7.6.1 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li class="current"><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li><a href="files.html"><span>File&#160;List</span></a></li>
<li class="current"><a href="globals.html"><span>File&#160;Members</span></a></li>
</ul>
</div>
<div id="navrow3" class="tabs2">
<ul class="tablist">
<li class="current"><a href="globals.html"><span>All</span></a></li>
<li><a href="globals_defs.html"><span>Defines</span></a></li>
</ul>
</div>
<div id="navrow4" class="tabs3">
<ul class="tablist">
<li><a href="#index_b"><span>b</span></a></li>
<li><a href="#index_c"><span>c</span></a></li>
<li><a href="#index_d"><span>d</span></a></li>
<li><a href="#index_h"><span>h</span></a></li>
<li><a href="#index_i"><span>i</span></a></li>
<li><a href="#index_m"><span>m</span></a></li>
<li><a href="#index_r"><span>r</span></a></li>
<li><a href="#index_s"><span>s</span></a></li>
<li><a href="#index_t"><span>t</span></a></li>
<li><a href="#index_v"><span>v</span></a></li>
</ul>
</div>
</div>
<div class="contents">
<div class="textblock">Here is a list of all file members with links to the files they belong to:</div>
<h3><a class="anchor" id="index_b"></a>- b -</h3><ul>
<li>BLANK_TIMING_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a42cb2ce84258587d514ec3268548ba89">TMC26XStepper.cpp</a>
</li>
<li>BLANK_TIMING_SHIFT
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#abdac78f7f2c506972265a8e5883e1eae">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_c"></a>- c -</h3><ul>
<li>CHOPPER_CONFIG_REGISTER
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a70a540d1090b989b8600b5e4776659fe">TMC26XStepper.cpp</a>
</li>
<li>CHOPPER_MODE_STANDARD
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a57418a67ff726d540b813230bca1d536">TMC26XStepper.cpp</a>
</li>
<li>CHOPPER_MODE_T_OFF_FAST_DECAY
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aaf1b564ced7de8ff3245c964e3775826">TMC26XStepper.cpp</a>
</li>
<li>COOL_STEP_HALF_CS_LIMIT
: <a class="el" href="_t_m_c26_x_stepper_8h.html#a28b1774bd4aa854fb5e4b6dc7db96ecb">TMC26XStepper.h</a>
</li>
<li>COOL_STEP_QUARTDER_CS_LIMIT
: <a class="el" href="_t_m_c26_x_stepper_8h.html#a1a4db5eafd0a9247677153cb4c8b7d54">TMC26XStepper.h</a>
</li>
<li>COOL_STEP_REGISTER
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab9828bfaa075a0a8647c709136016317">TMC26XStepper.cpp</a>
</li>
<li>CURRENT_DOWN_STEP_SPEED_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#adbe13a0464355e42fbe786ca5f58ed8d">TMC26XStepper.cpp</a>
</li>
<li>CURRENT_SCALING_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a99dcb8c6d98b0b54c23699a3f90450e4">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_d"></a>- d -</h3><ul>
<li>DEFAULT_MICROSTEPPING_VALUE
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a6560b3471273e99e280ba795e3469ede">TMC26XStepper.cpp</a>
</li>
<li>DOUBLE_EDGE_STEP
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a770601bf0153e4bc639b9c3005b15af7">TMC26XStepper.cpp</a>
</li>
<li>DRIVER_CONFIG_REGISTER
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#af35f569d42ea3b1d634901a3b6a908ee">TMC26XStepper.cpp</a>
</li>
<li>DRIVER_CONTROL_REGISTER
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a108f18bf4a30a0e0f0991ac0e4ce0579">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_h"></a>- h -</h3><ul>
<li>HYSTERESIS_DECREMENT_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a424c248097b38c1e29e6a58ad48e6bd9">TMC26XStepper.cpp</a>
</li>
<li>HYSTERESIS_DECREMENT_SHIFT
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a36e554a87785ce6ba998b79aae9e74e0">TMC26XStepper.cpp</a>
</li>
<li>HYSTERESIS_LOW_SHIFT
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a38ce0bb0fa20db28351ac9167f28db98">TMC26XStepper.cpp</a>
</li>
<li>HYSTERESIS_LOW_VALUE_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ad9d2302f6d61cd84a612a2e2bcdeb56e">TMC26XStepper.cpp</a>
</li>
<li>HYSTERESIS_START_VALUE_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a0de4e98b412dced62c3a4452b7483af3">TMC26XStepper.cpp</a>
</li>
<li>HYSTERESIS_START_VALUE_SHIFT
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac2c1c939256126e605396c4aaee3c804">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_i"></a>- i -</h3><ul>
<li>INITIAL_MICROSTEPPING
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a54a6d12e96d851361974b10614a00e45">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_m"></a>- m -</h3><ul>
<li>MICROSTEPPING_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8f5cb0c066109ffb18cefc0e85ee1d1b">TMC26XStepper.cpp</a>
</li>
<li>MINIMUM_CURRENT_FOURTH
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8a261a77d198b85f6dd8416387b354b3">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_r"></a>- r -</h3><ul>
<li>RANDOM_TOFF_TIME
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a64520580cffd416668f3b91bd60f84e1">TMC26XStepper.cpp</a>
</li>
<li>READ_MICROSTEP_POSTION
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a143b7757272f07866d9655bde8303d9a">TMC26XStepper.cpp</a>
</li>
<li>READ_SELECTION_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a88a4b45fa6385eba8aa4f0342334b832">TMC26XStepper.cpp</a>
</li>
<li>READ_STALL_GUARD_AND_COOL_STEP
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aef62b7fdcbac0b33b2d6e9cea4b5f9b2">TMC26XStepper.cpp</a>
</li>
<li>READ_STALL_GUARD_READING
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac1bd4da94fab7ce1049be2f866211819">TMC26XStepper.cpp</a>
</li>
<li>READOUT_VALUE_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a5c3d76da63f585e37813c32be2e11ab7">TMC26XStepper.cpp</a>
</li>
<li>REGISTER_BIT_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a3b02ee1f518b0c90c16488f937abd443">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_s"></a>- s -</h3><ul>
<li>SE_CURRENT_STEP_WIDTH_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aba6c07e5672e34e618bb3a550ab0d2bc">TMC26XStepper.cpp</a>
</li>
<li>SE_MAX_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac8f748bf735c447dbed7dd4c7b631a87">TMC26XStepper.cpp</a>
</li>
<li>SE_MIN_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae1862dfb958c03698b0abd95fda033ea">TMC26XStepper.cpp</a>
</li>
<li>STALL_GUARD2_LOAD_MEASURE_REGISTER
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a478d9bde09a6528eef6af6ffeeb6caba">TMC26XStepper.cpp</a>
</li>
<li>STALL_GUARD_CONFIG_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a99ac04f0615556fc13c0c9f3e1c1b49d">TMC26XStepper.cpp</a>
</li>
<li>STALL_GUARD_FILTER_ENABLED
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#afdbbefabd0c29c4b6e403c4663d0f0be">TMC26XStepper.cpp</a>
</li>
<li>STALL_GUARD_TRESHHOLD_VALUE_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae631457932894a974334892704550ecc">TMC26XStepper.cpp</a>
</li>
<li>STALL_GUARD_VALUE_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a6a1cb1fd61cf7c570f94376fa11fe55b">TMC26XStepper.cpp</a>
</li>
<li>STATUS_OPEN_LOAD_A
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae9cbbe5af7188e6bff8fe412f8e42f59">TMC26XStepper.cpp</a>
</li>
<li>STATUS_OPEN_LOAD_B
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab29dc5cd6c6c4e5bf99e71bd563e1be1">TMC26XStepper.cpp</a>
</li>
<li>STATUS_OVER_TEMPERATURE_SHUTDOWN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#adbb23d2f055c9eab55eac29d1a75deb4">TMC26XStepper.cpp</a>
</li>
<li>STATUS_OVER_TEMPERATURE_WARNING
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa317fd77f2f26fdfbfd331e21d9069e8">TMC26XStepper.cpp</a>
</li>
<li>STATUS_SHORT_TO_GROUND_A
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8e03041302a092174fa33b3cf837dca2">TMC26XStepper.cpp</a>
</li>
<li>STATUS_SHORT_TO_GROUND_B
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a903c3eba99695a32c6736463dcfd93ae">TMC26XStepper.cpp</a>
</li>
<li>STATUS_STALL_GUARD_STATUS
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa09ef662fd19bf2d063d6bd0f48eca14">TMC26XStepper.cpp</a>
</li>
<li>STATUS_STAND_STILL
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab96ed1635faee6650e9cce73598a2773">TMC26XStepper.cpp</a>
</li>
<li>STEP_INTERPOLATION
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa64245f223209654c60588e4558e0bab">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_t"></a>- t -</h3><ul>
<li>T_OFF_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa4e49237f2671e7f28aa34ae0e89da8d">TMC26XStepper.cpp</a>
</li>
<li>T_OFF_TIMING_PATERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a7659d842c803e47ba911a2a6e26327f3">TMC26XStepper.cpp</a>
</li>
<li>TMC26X_OVERTEMPERATURE_PREWARING
: <a class="el" href="_t_m_c26_x_stepper_8h.html#add42eee34f674f92c19bcd5266d2445f">TMC26XStepper.h</a>
</li>
<li>TMC26X_OVERTEMPERATURE_SHUTDOWN
: <a class="el" href="_t_m_c26_x_stepper_8h.html#adae814ce848677abd87758c7ac79a436">TMC26XStepper.h</a>
</li>
<li>TMC26X_READOUT_CURRENT
: <a class="el" href="_t_m_c26_x_stepper_8h.html#a01760ad15e3846536526a990efe47094">TMC26XStepper.h</a>
</li>
<li>TMC26X_READOUT_POSITION
: <a class="el" href="_t_m_c26_x_stepper_8h.html#aff05d4a47ef8821322ccc2a20785fbee">TMC26XStepper.h</a>
</li>
<li>TMC26X_READOUT_STALLGUARD
: <a class="el" href="_t_m_c26_x_stepper_8h.html#ac864ff8886123039c7d2d3c617f7ef87">TMC26XStepper.h</a>
</li>
</ul>
<h3><a class="anchor" id="index_v"></a>- v -</h3><ul>
<li>VSENSE
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a4fb1c008e2ff76eee9362600eed112e1">TMC26XStepper.cpp</a>
</li>
</ul>
</div><!-- contents -->
<hr class="footer"/><address class="footer"><small>
Generated on Mon Nov 19 2012 20:26:21 for Trinamic TMC26X Stepper Driver for Arduino by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.7.6.1
</small></address>
</body>
</html>

View file

@ -0,0 +1,289 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<title>Trinamic TMC26X Stepper Driver for Arduino: File Members</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td style="padding-left: 0.5em;">
<div id="projectname">Trinamic TMC26X Stepper Driver for Arduino
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- Generated by Doxygen 1.7.6.1 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li class="current"><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li><a href="files.html"><span>File&#160;List</span></a></li>
<li class="current"><a href="globals.html"><span>File&#160;Members</span></a></li>
</ul>
</div>
<div id="navrow3" class="tabs2">
<ul class="tablist">
<li><a href="globals.html"><span>All</span></a></li>
<li class="current"><a href="globals_defs.html"><span>Defines</span></a></li>
</ul>
</div>
<div id="navrow4" class="tabs3">
<ul class="tablist">
<li><a href="#index_b"><span>b</span></a></li>
<li><a href="#index_c"><span>c</span></a></li>
<li><a href="#index_d"><span>d</span></a></li>
<li><a href="#index_h"><span>h</span></a></li>
<li><a href="#index_i"><span>i</span></a></li>
<li><a href="#index_m"><span>m</span></a></li>
<li><a href="#index_r"><span>r</span></a></li>
<li><a href="#index_s"><span>s</span></a></li>
<li><a href="#index_t"><span>t</span></a></li>
<li><a href="#index_v"><span>v</span></a></li>
</ul>
</div>
</div>
<div class="contents">
&#160;
<h3><a class="anchor" id="index_b"></a>- b -</h3><ul>
<li>BLANK_TIMING_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a42cb2ce84258587d514ec3268548ba89">TMC26XStepper.cpp</a>
</li>
<li>BLANK_TIMING_SHIFT
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#abdac78f7f2c506972265a8e5883e1eae">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_c"></a>- c -</h3><ul>
<li>CHOPPER_CONFIG_REGISTER
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a70a540d1090b989b8600b5e4776659fe">TMC26XStepper.cpp</a>
</li>
<li>CHOPPER_MODE_STANDARD
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a57418a67ff726d540b813230bca1d536">TMC26XStepper.cpp</a>
</li>
<li>CHOPPER_MODE_T_OFF_FAST_DECAY
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aaf1b564ced7de8ff3245c964e3775826">TMC26XStepper.cpp</a>
</li>
<li>COOL_STEP_HALF_CS_LIMIT
: <a class="el" href="_t_m_c26_x_stepper_8h.html#a28b1774bd4aa854fb5e4b6dc7db96ecb">TMC26XStepper.h</a>
</li>
<li>COOL_STEP_QUARTDER_CS_LIMIT
: <a class="el" href="_t_m_c26_x_stepper_8h.html#a1a4db5eafd0a9247677153cb4c8b7d54">TMC26XStepper.h</a>
</li>
<li>COOL_STEP_REGISTER
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab9828bfaa075a0a8647c709136016317">TMC26XStepper.cpp</a>
</li>
<li>CURRENT_DOWN_STEP_SPEED_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#adbe13a0464355e42fbe786ca5f58ed8d">TMC26XStepper.cpp</a>
</li>
<li>CURRENT_SCALING_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a99dcb8c6d98b0b54c23699a3f90450e4">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_d"></a>- d -</h3><ul>
<li>DEFAULT_MICROSTEPPING_VALUE
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a6560b3471273e99e280ba795e3469ede">TMC26XStepper.cpp</a>
</li>
<li>DOUBLE_EDGE_STEP
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a770601bf0153e4bc639b9c3005b15af7">TMC26XStepper.cpp</a>
</li>
<li>DRIVER_CONFIG_REGISTER
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#af35f569d42ea3b1d634901a3b6a908ee">TMC26XStepper.cpp</a>
</li>
<li>DRIVER_CONTROL_REGISTER
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a108f18bf4a30a0e0f0991ac0e4ce0579">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_h"></a>- h -</h3><ul>
<li>HYSTERESIS_DECREMENT_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a424c248097b38c1e29e6a58ad48e6bd9">TMC26XStepper.cpp</a>
</li>
<li>HYSTERESIS_DECREMENT_SHIFT
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a36e554a87785ce6ba998b79aae9e74e0">TMC26XStepper.cpp</a>
</li>
<li>HYSTERESIS_LOW_SHIFT
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a38ce0bb0fa20db28351ac9167f28db98">TMC26XStepper.cpp</a>
</li>
<li>HYSTERESIS_LOW_VALUE_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ad9d2302f6d61cd84a612a2e2bcdeb56e">TMC26XStepper.cpp</a>
</li>
<li>HYSTERESIS_START_VALUE_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a0de4e98b412dced62c3a4452b7483af3">TMC26XStepper.cpp</a>
</li>
<li>HYSTERESIS_START_VALUE_SHIFT
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac2c1c939256126e605396c4aaee3c804">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_i"></a>- i -</h3><ul>
<li>INITIAL_MICROSTEPPING
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a54a6d12e96d851361974b10614a00e45">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_m"></a>- m -</h3><ul>
<li>MICROSTEPPING_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8f5cb0c066109ffb18cefc0e85ee1d1b">TMC26XStepper.cpp</a>
</li>
<li>MINIMUM_CURRENT_FOURTH
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8a261a77d198b85f6dd8416387b354b3">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_r"></a>- r -</h3><ul>
<li>RANDOM_TOFF_TIME
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a64520580cffd416668f3b91bd60f84e1">TMC26XStepper.cpp</a>
</li>
<li>READ_MICROSTEP_POSTION
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a143b7757272f07866d9655bde8303d9a">TMC26XStepper.cpp</a>
</li>
<li>READ_SELECTION_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a88a4b45fa6385eba8aa4f0342334b832">TMC26XStepper.cpp</a>
</li>
<li>READ_STALL_GUARD_AND_COOL_STEP
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aef62b7fdcbac0b33b2d6e9cea4b5f9b2">TMC26XStepper.cpp</a>
</li>
<li>READ_STALL_GUARD_READING
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac1bd4da94fab7ce1049be2f866211819">TMC26XStepper.cpp</a>
</li>
<li>READOUT_VALUE_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a5c3d76da63f585e37813c32be2e11ab7">TMC26XStepper.cpp</a>
</li>
<li>REGISTER_BIT_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a3b02ee1f518b0c90c16488f937abd443">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_s"></a>- s -</h3><ul>
<li>SE_CURRENT_STEP_WIDTH_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aba6c07e5672e34e618bb3a550ab0d2bc">TMC26XStepper.cpp</a>
</li>
<li>SE_MAX_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac8f748bf735c447dbed7dd4c7b631a87">TMC26XStepper.cpp</a>
</li>
<li>SE_MIN_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae1862dfb958c03698b0abd95fda033ea">TMC26XStepper.cpp</a>
</li>
<li>STALL_GUARD2_LOAD_MEASURE_REGISTER
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a478d9bde09a6528eef6af6ffeeb6caba">TMC26XStepper.cpp</a>
</li>
<li>STALL_GUARD_CONFIG_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a99ac04f0615556fc13c0c9f3e1c1b49d">TMC26XStepper.cpp</a>
</li>
<li>STALL_GUARD_FILTER_ENABLED
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#afdbbefabd0c29c4b6e403c4663d0f0be">TMC26XStepper.cpp</a>
</li>
<li>STALL_GUARD_TRESHHOLD_VALUE_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae631457932894a974334892704550ecc">TMC26XStepper.cpp</a>
</li>
<li>STALL_GUARD_VALUE_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a6a1cb1fd61cf7c570f94376fa11fe55b">TMC26XStepper.cpp</a>
</li>
<li>STATUS_OPEN_LOAD_A
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae9cbbe5af7188e6bff8fe412f8e42f59">TMC26XStepper.cpp</a>
</li>
<li>STATUS_OPEN_LOAD_B
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab29dc5cd6c6c4e5bf99e71bd563e1be1">TMC26XStepper.cpp</a>
</li>
<li>STATUS_OVER_TEMPERATURE_SHUTDOWN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#adbb23d2f055c9eab55eac29d1a75deb4">TMC26XStepper.cpp</a>
</li>
<li>STATUS_OVER_TEMPERATURE_WARNING
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa317fd77f2f26fdfbfd331e21d9069e8">TMC26XStepper.cpp</a>
</li>
<li>STATUS_SHORT_TO_GROUND_A
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8e03041302a092174fa33b3cf837dca2">TMC26XStepper.cpp</a>
</li>
<li>STATUS_SHORT_TO_GROUND_B
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a903c3eba99695a32c6736463dcfd93ae">TMC26XStepper.cpp</a>
</li>
<li>STATUS_STALL_GUARD_STATUS
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa09ef662fd19bf2d063d6bd0f48eca14">TMC26XStepper.cpp</a>
</li>
<li>STATUS_STAND_STILL
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab96ed1635faee6650e9cce73598a2773">TMC26XStepper.cpp</a>
</li>
<li>STEP_INTERPOLATION
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa64245f223209654c60588e4558e0bab">TMC26XStepper.cpp</a>
</li>
</ul>
<h3><a class="anchor" id="index_t"></a>- t -</h3><ul>
<li>T_OFF_PATTERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa4e49237f2671e7f28aa34ae0e89da8d">TMC26XStepper.cpp</a>
</li>
<li>T_OFF_TIMING_PATERN
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a7659d842c803e47ba911a2a6e26327f3">TMC26XStepper.cpp</a>
</li>
<li>TMC26X_OVERTEMPERATURE_PREWARING
: <a class="el" href="_t_m_c26_x_stepper_8h.html#add42eee34f674f92c19bcd5266d2445f">TMC26XStepper.h</a>
</li>
<li>TMC26X_OVERTEMPERATURE_SHUTDOWN
: <a class="el" href="_t_m_c26_x_stepper_8h.html#adae814ce848677abd87758c7ac79a436">TMC26XStepper.h</a>
</li>
<li>TMC26X_READOUT_CURRENT
: <a class="el" href="_t_m_c26_x_stepper_8h.html#a01760ad15e3846536526a990efe47094">TMC26XStepper.h</a>
</li>
<li>TMC26X_READOUT_POSITION
: <a class="el" href="_t_m_c26_x_stepper_8h.html#aff05d4a47ef8821322ccc2a20785fbee">TMC26XStepper.h</a>
</li>
<li>TMC26X_READOUT_STALLGUARD
: <a class="el" href="_t_m_c26_x_stepper_8h.html#ac864ff8886123039c7d2d3c617f7ef87">TMC26XStepper.h</a>
</li>
</ul>
<h3><a class="anchor" id="index_v"></a>- v -</h3><ul>
<li>VSENSE
: <a class="el" href="_t_m_c26_x_stepper_8cpp.html#a4fb1c008e2ff76eee9362600eed112e1">TMC26XStepper.cpp</a>
</li>
</ul>
</div><!-- contents -->
<hr class="footer"/><address class="footer"><small>
Generated on Mon Nov 19 2012 20:26:21 for Trinamic TMC26X Stepper Driver for Arduino by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.7.6.1
</small></address>
</body>
</html>

View file

@ -0,0 +1,72 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<title>Trinamic TMC26X Stepper Driver for Arduino: TMC 260, 261, 262 Stepper Driver for Arduino</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td style="padding-left: 0.5em;">
<div id="projectname">Trinamic TMC26X Stepper Driver for Arduino
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- Generated by Doxygen 1.7.6.1 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li class="current"><a href="index.html"><span>Main&#160;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
</div>
<div class="header">
<div class="headertitle">
<div class="title">TMC 260, 261, 262 Stepper Driver for Arduino </div> </div>
</div><!--header-->
<div class="contents">
<div class="textblock"><dl class="author"><dt><b>Author:</b></dt><dd>Interactive MAtter, MArcus Nowotny, <a href="mailto:marcus@interactive-matter.eu">marcus@interactive-matter.eu</a> </dd></dl>
<h2><a class="anchor" id="HOWTO"></a>
How to use the driver</h2>
<p>Here we go with aminial how to description</p>
<h2><a class="anchor" id="COPYRIGHT_NOTIFICATION"></a>
COPYRIGHT NOTIFICATION</h2>
<dl class="user"><dt><b>(c) 2011 Interactive MAtter, Marcus Nowotny </b></dt><dd></dd></dl>
<dl class="user"><dt><b></b></dt><dd>Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:</dd></dl>
<p>The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.</p>
<p>THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. </p>
</div></div><!-- contents -->
<hr class="footer"/><address class="footer"><small>
Generated on Mon Nov 19 2012 20:26:21 for Trinamic TMC26X Stepper Driver for Arduino by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.7.6.1
</small></address>
</body>
</html>

File diff suppressed because one or more lines are too long

View file

@ -0,0 +1,68 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<title>Trinamic TMC26X Stepper Driver for Arduino: mainpage.dox File Reference</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td style="padding-left: 0.5em;">
<div id="projectname">Trinamic TMC26X Stepper Driver for Arduino
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- Generated by Doxygen 1.7.6.1 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li class="current"><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li><a href="files.html"><span>File&#160;List</span></a></li>
<li><a href="globals.html"><span>File&#160;Members</span></a></li>
</ul>
</div>
</div>
<div class="header">
<div class="headertitle">
<div class="title">mainpage.dox File Reference</div> </div>
</div><!--header-->
<div class="contents">
</div><!-- contents -->
<hr class="footer"/><address class="footer"><small>
Generated on Mon Nov 19 2012 20:26:21 for Trinamic TMC26X Stepper Driver for Arduino by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.7.6.1
</small></address>
</body>
</html>

Binary file not shown.

After

Width:  |  Height:  |  Size: 159 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 97 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 118 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 140 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 178 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 192 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 189 B

View file

@ -0,0 +1,59 @@
.tabs, .tabs2, .tabs3 {
background-image: url('tab_b.png');
width: 100%;
z-index: 101;
font-size: 13px;
}
.tabs2 {
font-size: 10px;
}
.tabs3 {
font-size: 9px;
}
.tablist {
margin: 0;
padding: 0;
display: table;
}
.tablist li {
float: left;
display: table-cell;
background-image: url('tab_b.png');
line-height: 36px;
list-style: none;
}
.tablist a {
display: block;
padding: 0 20px;
font-weight: bold;
background-image:url('tab_s.png');
background-repeat:no-repeat;
background-position:right;
color: #283A5D;
text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9);
text-decoration: none;
outline: none;
}
.tabs3 .tablist a {
padding: 0 10px;
}
.tablist a:hover {
background-image: url('tab_h.png');
background-repeat:repeat-x;
color: #fff;
text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0);
text-decoration: none;
}
.tablist li.current a {
background-image: url('tab_a.png');
background-repeat:repeat-x;
color: #fff;
text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0);
}

View file

@ -0,0 +1,82 @@
/*
TMC26XExample.ino - - TMC26X Stepper library Example for Wiring/Arduino
Copyright (c) 2011, Interactive Matter, Marcus Nowotny
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
#include <SPI.h>
#include <TMC26XStepper.h>
//we have a stepper motor with 200 steps per rotation, CS pin 2, dir pin 6, step pin 7 and a current of 300mA
TMC26XStepper tmc26XStepper = TMC26XStepper(200,2,6,7,700);
int curr_step;
int speed = 0;
int speedDirection = 100;
int maxSpeed = 1000;
void setup() {
Serial.begin(9600);
Serial.println("==============================");
Serial.println("TMC26X Stepper Driver Demo App");
Serial.println("==============================");
//set this according to you stepper
Serial.println("Configuring stepper driver");
//char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement
tmc26XStepper.setSpreadCycleChopper(2,24,8,6,0);
tmc26XStepper.setRandomOffTime(0);
tmc26XStepper.setMicrosteps(32);
tmc26XStepper.setStallGuardThreshold(4,0);
Serial.println("config finished, starting");
tmc26XStepper.start();
Serial.println("started");
}
void loop() {
if (!tmc26XStepper.isMoving()) {
speed+=speedDirection;
if (speed>maxSpeed) {
speed = maxSpeed;
speedDirection = -speedDirection;
} else if (speed<0) {
speedDirection = -speedDirection;
speed=speedDirection;
}
//setting the speed
Serial.print("setting speed to ");
Serial.println(speed);
tmc26XStepper.setSpeed(speed);
//we want some kind of constant running time - so the length is just a product of speed
Serial.print("Going ");
Serial.print(10*speed);
Serial.println(" steps");
tmc26XStepper.step(10*speed);
} else {
//we put out the status every 100 steps
if (tmc26XStepper.getStepsLeft()%100==0) {
Serial.print("Stall Guard: ");
Serial.println(tmc26XStepper.getCurrentStallGuardReading());
}
}
tmc26XStepper.move();
}

View file

@ -0,0 +1,176 @@
/*
TMC26XMotorTest.ino - - TMC26X Stepper library tester for Wiring/Arduino
Copyright (c) 2011, Interactive Matter, Marcus Nowotny
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
unsigned int motor_counter = 0;
unsigned char motor_moved = 0;
int sgThreshold = 4;
int sgFilter = 0;
int direction = 1;
unsigned int lower_SG_threshold = 0;
unsigned int upper_SG_threshold = 0;
unsigned char number_of_SG_readings=0;
unsigned char current_increment_step_size=0;
unsigned char lower_current_limit=0;
char chopperMode = 0; //0 for spread, 1 for constant off
char t_off = 2;
char t_blank = 24;
char h_start = 8;
char h_end = 6;
char h_decrement = 0;
void startMotor() {
Serial.println(F("Configuring stepper driver"));
//char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement
tmc26XStepper.setSpreadCycleChopper(t_off,t_blank,h_start,h_end,h_decrement);
tmc26XStepper.setRandomOffTime(0);
tmc26XStepper.setMicrosteps(32);
tmc26XStepper.setStallGuardThreshold(sgThreshold,sgFilter);
// Serial.println("config finished, starting");
digitalWrite(ENABLE_PIN,LOW);
tmc26XStepper.start();
tmc26XStepper.setSpeed(10);
TCNT2=setupTimer2(10000);
sei();
}
void runMotor() {
if (running && !tmc26XStepper.isMoving()) {
tmc26XStepper.step(direction*10000);
Serial.println("run");
}
if (!running & tmc26XStepper.isMoving()) {
tmc26XStepper.stop();
Serial.println("stop");
}
}
void setSpeed(unsigned int targetSpeed) {
if (targetSpeed>0 && targetSpeed<MAX_SPEED) {
Serial.print(F("Setting speed: "));
Serial.println(targetSpeed);
tmc26XStepper.setSpeed(targetSpeed);
}
else {
Serial.print(F("improper speed "));
Serial.println(targetSpeed);
}
}
void setMicrostepping(int microstepping) {
if (microstepping<1 || microstepping>256) {
Serial.print(F("Improperd microstepping setting [1...256]: "));
Serial.print(microstepping);
}
else {
tmc26XStepper.setMicrosteps(microstepping);
}
}
void setStallGuardThreshold(int threshold) {
if (threshold<-64 || threshold > 63) {
Serial.print(F("Improper Stall Guard Threshold [-64...63]: "));
Serial.println(threshold);
}
else {
sgThreshold = threshold;
tmc26XStepper.setStallGuardThreshold(threshold,sgFilter);
}
}
void setStallGuardFilter(int filter) {
if (filter) {
sgFilter=1;
}
else {
sgFilter=0;
}
tmc26XStepper.setStallGuardThreshold(sgThreshold,sgFilter);
}
void setCurrent(int current) {
if (current>0 && current <1700) {
tmc26XStepper.setCurrent(current);
}
else {
Serial.print(F("Improper current {0 ... 1200}: "));
Serial.print(current);
}
}
void updateChopper() {
//we can do only spread now
if (chopperMode==0) {
tmc26XStepper.setSpreadCycleChopper(t_off,t_blank,h_start,h_end,h_decrement);
}
}
void updateCoolStep() {
tmc26XStepper.setCoolStepConfiguration(
lower_SG_threshold, upper_SG_threshold, number_of_SG_readings,
current_increment_step_size, lower_current_limit);
}
//from http://www.uchobby.com/index.php/2007/11/24/arduino-interrupts/
//Setup Timer2.s
//Configures the ATMega168 8-Bit Timer2 to generate an interrupt
//at the specified frequency.
//Returns the timer load value which must be loaded into TCNT2
//inside your ISR routine.
//See the example usage below.
unsigned char setupTimer2(float timeoutFrequency){
unsigned char result; //The timer load value.
//Calculate the timer load value
result=(int)((257.0-(TIMER_CLOCK_FREQ/timeoutFrequency))+0.5);
//The 257 really should be 256 but I get better results with 257.
//Timer2 Settings: Timer Prescaler /8, mode 0
//Timer clock = 16MHz/8 = 2Mhz or 0.5us
//The /8 prescale gives us a good range to work with
//so we just hard code this for now.
TCCR2A = 0;
TCCR2B = 0<<CS22 | 1<<CS21 | 0<<CS20;
//Timer2 Overflow Interrupt Enable
TIMSK2 = 1<<TOIE2;
//load the timer for its first cycle
TCNT2=result;
return(result);
}
ISR(TIMER2_OVF_vect) {
motor_moved = tmc26XStepper.move();
motor_counter++;
}

View file

@ -0,0 +1,369 @@
/*
TMC26XMotorTest.ino - - TMC26X Stepper library tester for Wiring/Arduino
Copyright (c) 2011, Interactive Matter, Marcus Nowotny
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
#define INPUT_BUFFER_LENGTH 32
#define SERIAL_SPEED 115200
#define STATUS_COUNTER 100
char inputBuffer[INPUT_BUFFER_LENGTH+1]; //ad on character to keep the trainling 0
unsigned char inputBufferPosition;
void startSerial() {
Serial.begin(SERIAL_SPEED);
Serial.println(F("================================="));
Serial.println(F("TMC26X Stepper Driver Motor Tester"));
Serial.println(F("================================="));
//empty the input buffer
for (unsigned char i=0; i< INPUT_BUFFER_LENGTH+1; i++) {
inputBuffer[i]=0;
}
inputBufferPosition=0;
}
void loopSerial() {
if (Serial.available()>0 && inputBufferPosition<INPUT_BUFFER_LENGTH) {
char c = Serial.read();
//Read the char
inputBuffer[inputBufferPosition]=c;
inputBufferPosition++;
//always terminate the string
inputBuffer[inputBufferPosition]=0;
//and if the line ended we execute the command
if (c=='\n') {
executeSerialCommand();
}
}
if (motor_moved) {
Serial.print("#sg");
Serial.print(tmc26XStepper.getCurrentStallGuardReading(),DEC);
Serial.print(",p");
Serial.print(tmc26XStepper.getMotorPosition(),DEC);
Serial.print(",k");
Serial.print(tmc26XStepper.getCurrentCurrent(),DEC);
Serial.println(',');
motor_moved=0;
}
if (motor_counter>STATUS_COUNTER) {
motor_counter=0;
char moving = tmc26XStepper.isMoving();
Serial.print('#');
if (moving) {
Serial.print('r');
}
else {
Serial.print('s');
}
Serial.print(',');
Serial.print('d');
Serial.print(direction);
Serial.print(',');
Serial.print("c");
Serial.print(tmc26XStepper.getCurrent(),DEC);
Serial.print(',');
Serial.print('S');
Serial.print(tmc26XStepper.getSpeed(),DEC);
Serial.print(',');
Serial.print('m');
Serial.print(tmc26XStepper.getMicrosteps(),DEC);
Serial.print(',');
Serial.print("t");
Serial.print(tmc26XStepper.getStallGuardThreshold(),DEC);
Serial.print(',');
Serial.print('f');
Serial.print(tmc26XStepper.getStallGuardFilter(),DEC);
Serial.print(',');
//print out the general cool step config
if (tmc26XStepper.isCoolStepEnabled()) {
Serial.print("Ke+,");
}
else {
Serial.print("Ke-,");
}
Serial.print("Kl");
Serial.print(tmc26XStepper.getCoolStepLowerSgThreshold(),DEC);
Serial.print(",Ku");
Serial.print(tmc26XStepper.getCoolStepUpperSgThreshold(),DEC);
Serial.print(",Kn");
Serial.print(tmc26XStepper.getCoolStepNumberOfSGReadings(),DEC);
Serial.print(",Ki");
Serial.print(tmc26XStepper.getCoolStepCurrentIncrementSize(),DEC);
Serial.print(",Km");
Serial.print(tmc26XStepper.getCoolStepLowerCurrentLimit(),DEC);
Serial.print(',');
//detect the winding status
if (tmc26XStepper.isOpenLoadA()) {
Serial.print("ao,");
}
else if(tmc26XStepper.isShortToGroundA()) {
Serial.print("ag,");
}
else {
Serial.print("a-,");
}
//detect the winding status
if (tmc26XStepper.isOpenLoadB()) {
Serial.print("bo,");
}
else if(tmc26XStepper.isShortToGroundB()) {
Serial.print("bg,");
}
else {
Serial.print("b-,");
}
char temperature = tmc26XStepper.getOverTemperature();
if (temperature==0) {
Serial.print("x-,");
}
else if (temperature==TMC26X_OVERTEMPERATURE_PREWARING) {
Serial.print("xw,");
}
else {
Serial.print("xe,");
}
if (tmc26XStepper.isEnabled()) {
Serial.print("e1,");
}
else {
Serial.print("e0,");
}
//write out the current chopper config
Serial.print("Cm");
Serial.print(chopperMode,DEC);
Serial.print(",Co");
Serial.print(t_off,DEC);
Serial.print(",Cb");
Serial.print(t_blank,DEC);
if (chopperMode==0) {
Serial.print(",Cs");
Serial.print(h_start,DEC);
Serial.print(",Ce");
Serial.print(h_end,DEC);
Serial.print(",Cd");
Serial.print(h_decrement,DEC);
}
Serial.print(',');
Serial.println();
}
}
void executeSerialCommand() {
Serial.print("Executing ");
Serial.println(inputBuffer);
//stimple runn & stop commands
switch(inputBuffer[0]) {
case 's':
running = 0;
break;
case 'r':
running = -1;
break;
case 'S':
{
int targetSpeed = decode(1);
setSpeed(targetSpeed);
}
break;
case 'm':
{
int microstepping = decode(1);
setMicrostepping(microstepping);
}
break;
case 't':
{
int threshold = decode(1);
setStallGuardThreshold(threshold);
}
break;
case 'f':
{
int filter = decode(1);
setStallGuardFilter(filter);
}
break;
case 'd':
{
int value = decode(1);
tmc26XStepper.stop();
if (value<0) {
direction=-1;
}
else {
direction=1;
}
}
break;
case 'c':
{
int current = decode(1);
setCurrent(current);
}
break;
case 'e':
{
int enabled = decode(1);
if (enabled) {
tmc26XStepper.setEnabled(true);
}
else {
tmc26XStepper.setEnabled(false);
}
}
break;
case 'C':
switch(inputBuffer[1]) {
case 'o':
{
int value = decode(2);
if (value>0 && value<16) {
t_off=value;
updateChopper();
}
}
break;
case 'b':
{
int value = decode(2);
if (value>=0 && value<=3) {
t_blank=value;
updateChopper();
}
}
break;
case 's':
{
int value = decode(2);
if (value>=0 && value<=8) {
h_start=value;
updateChopper();
}
}
break;
case 'e':
{
int value = decode(2);
if (value>=-3 && value<=12) {
h_end=value;
updateChopper();
}
}
break;
case 'd':
{
int value = decode(2);
if (value>=0 && value<=3) {
h_decrement=value;
updateChopper();
}
}
break;
}
break;
case 'K':
switch(inputBuffer[1]) {
case '+':
tmc26XStepper.setCoolStepEnabled(true);
break;
case '-':
tmc26XStepper.setCoolStepEnabled(false);
break;
case 'l':
{
int value = decode(2);
if (value>=0 && value<480) {
lower_SG_threshold=value;
updateCoolStep();
}
}
break;
case 'u':
{
int value = decode(2);
if (value>=0 && value<480) {
upper_SG_threshold=value;
updateCoolStep();
}
}
break;
case 'n':
{
int value = decode(2);
if (value>=0 && value<4) {
number_of_SG_readings=value;
updateCoolStep();
}
}
break;
case 'i':
{
int value = decode(2);
if (value>=0 && value<4) {
current_increment_step_size=value;
updateCoolStep();
}
}
break;
case 'm':
{
int value = decode(2);
if (value>=0 && value<2) {
lower_current_limit=value;
updateCoolStep();
}
}
break;
}
break;
}
//at the end delete buffer
inputBufferPosition=0;
inputBuffer[0]=0;
}
int decode(unsigned char startPosition) {
int result=0;
boolean negative = false;
if (inputBuffer[startPosition]=='-') {
negative=true;
startPosition++;
}
for (unsigned char i=startPosition; i< (INPUT_BUFFER_LENGTH+1) && inputBuffer[i]!=0; i++) {
char number = inputBuffer[i];
//this very dumb approac can lead to errors, but we expect only numbers after the command anyway
if (number <= '9' && number >='0') {
result *= 10;
result += number - '0';
}
}
if (negative) {
return -result;
}
else {
return result;
}
}

View file

@ -0,0 +1,61 @@
/*
TMC26XMotorTest.ino - - TMC26X Stepper library Example for Wiring/Arduino
Copyright (c) 2011, Interactive Matter, Marcus Nowotny
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
#include <SPI.h>
#include <TMC26XStepper.h>
//you may adapt this to your shield or breakout board connection
#define CS_PIN 2
#define DIR_PIN 6
#define STEP_PIN 7
#define ENABLE_PIN 8 //if it is not connected it won't be a problem
#define TIMER_CLOCK_FREQ 2000000.0 //2MHz for /8 prescale from 16MHz
#define INITIAL_CURRENT 500 //in mA
#define MAX_SPEED 1000
//we have a stepper motor with 200 steps per rotation, CS pin 2, dir pin 3, step pin 4 and a current of 300mA
TMC26XStepper tmc26XStepper = TMC26XStepper(200,CS_PIN,DIR_PIN,STEP_PIN,INITIAL_CURRENT);
char running;
void setup() {
//configure the enable pin
pinMode(ENABLE_PIN, OUTPUT);
digitalWrite(ENABLE_PIN,HIGH);
startSerial();
startMotor();
//set this according to you stepper
Serial.println(F("started"));
}
void loop() {
loopSerial();
runMotor();
}

View file

@ -0,0 +1,306 @@
/*
TMC26XMotorTest.pde - - TMC26X Stepper Tester for Processing
Copyright (c) 2011, Interactive Matter, Marcus Nowotny
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
String channelAStatus=null;
String channelBStatus=null;
String temperatureStatus=null;
boolean motor_connected = false;
RadioButton serialButtons;
Button serialOkButton;
Button helpButton;
Textarea statusArea;
String[] ports;
int activePortIndex = -1;
String identString="TMC26X Stepper Driver Motor Tester";
int connectTimeout=10*1000; //how long do we wait until the Arduino is connected
StringBuilder serialStringBuilder = new StringBuilder();
void setupSerialConfig() {
Tab defaultTab = controlP5.getTab("default");
//add the list of serial interfaces - it get's populated later
serialButtons = controlP5.addRadioButton("serialport", 200, 100+TMCLogo.height*2+50);
serialConfigElements.add(serialButtons);
serialButtons.captionLabel().set("Select Serial Port");
serialButtons.showBar();
serialButtons.moveTo(defaultTab);
//ad the ok button
serialOkButton = controlP5.addButton("serialOk", 1, 200, height-300, 30, 30);
serialConfigElements.add(serialOkButton);
serialOkButton.setCaptionLabel("OK");
runToggle.moveTo(defaultTab);
//add the status area
statusArea = controlP5.addTextarea("statusArea","",200,height-250,300,50);
serialConfigElements.add(statusArea);
statusArea.moveTo(defaultTab);
helpButton = controlP5.addButton("help", 1, 200, height-250, 80, 30);
serialConfigElements.add(helpButton);
helpButton.moveTo(defaultTab);
//finally update the list of serial ports
updateSerialPortList();
}
void updateSerialPortList() {
//first remove all present serial ports
List items = serialButtons.getItems();
for (Object i:items) {
Toggle item = (Toggle) i;
serialButtons.removeItem(item.getName());
}
//add the serial ports
ports = Serial.list();
for (int i=0; i< ports.length; i++) {
serialButtons.addItem(ports[i],i);
}
serialButtons.setValue(-1);
serialOkButton.setVisible(false);
}
void serialport(int value) {
//ok button is only active if a serial port is selected
serialOkButton.setVisible(value>-1);
if (value>-1) {
statusArea.setText("");
}
activePortIndex = value;
}
void serialOk(int value) {
String error = null;
if (value!=0 && activePortIndex>-1) {
try {
arduinoPort = new Serial(this, ports[activePortIndex], 115200);
int timeStarted = millis();
StringBuilder identBuffer = new StringBuilder();
while (!motor_connected && (millis()-timeStarted)<connectTimeout) {
if (arduinoPort.available ()>0) {
char c = arduinoPort.readChar();
identBuffer.append(c);
if (c=='\n') {
if (identString.contains(identString)) {
motor_connected = true;
toggleUi(true);
return;
}
identBuffer = new StringBuilder();
}
}
}
} catch (RuntimeException e) {
//we simply do nothing
//TODO set status label
error = "There was a problem with serial port "+ports[activePortIndex]+": "+e.getMessage();
}
//ok appearantly we did not find an motor tester - so lets deselect that port
if (error == null) {
error = "Could not find TMC26XMotorTester on serial port "+ports[activePortIndex];
}
statusArea.setText(error);
Toggle selected = serialButtons.getItem(activePortIndex);
selected.setState(false);
serialOkButton.setVisible(false);
}
}
void decodeSerial() {
if (motor_connected) {
while (arduinoPort.available ()>0) {
char c = arduinoPort.readChar();
serialStringBuilder.append(c);
if (c=='\n') {
decodeSerial(serialStringBuilder.toString());
serialStringBuilder = new StringBuilder();
}
}
}
}
void sendCommand(String command) {
if (motor_connected) {
arduinoPort.write(command+"\n");
}
}
void decodeSerial(String line) {
settingStatus=true;
if (line.startsWith("#")) {
String status = line.substring(1);
StringTokenizer statusTokenizer = new StringTokenizer(status, ",");
while (statusTokenizer.hasMoreTokens ()) {
String statusToken = statusTokenizer.nextToken();
if ("s".equals(statusToken)) {
runToggle.setValue(0);
}
else if ("r".equals(statusToken)) {
runToggle.setValue(1);
}
else if (statusToken.startsWith("e")) {
int enabled = getValueOfToken(statusToken, 1);
if (enabled!=0) {
enabledToggle.setValue(1);
}
else {
enabledToggle.setValue(0);
}
}
else if (statusToken.startsWith("S")) {
speedSlider.setValue(getValueOfToken(statusToken, 1));
}
else if (statusToken.startsWith("m")) {
microsteppingButtons.activate("m_1/"+String.valueOf(getValueOfToken(statusToken, 1)));
}
else if (statusToken.startsWith("sg")) {
addStallGuardReading(getValueOfToken(statusToken, 2));
}
else if (statusToken.startsWith("p")) {
addPositionReading(getValueOfToken(statusToken, 1));
}
else if (statusToken.startsWith("k")) {
addCurrentReading(getValueOfToken(statusToken, 1));
}
else if (statusToken.startsWith("t")) {
sgtSlider.setValue(getValueOfToken(statusToken, 1));
}
else if (statusToken.startsWith("f")) {
sgFilterToggle.setValue(getValueOfToken(statusToken, 1));
}
else if (statusToken.startsWith("d")) {
setDirection(getValueOfToken(statusToken, 1));
}
else if (statusToken.startsWith("c")) {
setCurrent(getValueOfToken(statusToken, 1));
}
else if (statusToken.startsWith("a")) {
if (statusToken.charAt(1)=='o') {
channelAStatus="Open Load";
}
else if (statusToken.charAt(1)=='g') {
channelAStatus="Short to Ground!";
}
else {
channelAStatus=null;
}
}
else if (statusToken.startsWith("b")) {
if (statusToken.charAt(1)=='o') {
channelBStatus="Open Load";
}
else if (statusToken.charAt(1)=='g') {
channelBStatus="Short to Ground!";
}
else {
channelBStatus=null;
}
}
else if (statusToken.startsWith("x")) {
if (statusToken.charAt(1)=='w') {
temperatureStatus="Prewarning!";
}
else if (statusToken.charAt(1)=='e') {
temperatureStatus="Error";
}
else {
temperatureStatus=null;
}
}
else if (statusToken.startsWith("Cm")) {
//chopper mode is currently ignored
}
else if (statusToken.startsWith("Co")) {
constantOffSlider.setValue(getValueOfToken(statusToken, 2));
}
else if (statusToken.startsWith("Cb")) {
blankTimeSlider.setValue(getValueOfToken(statusToken, 2));
}
else if (statusToken.startsWith("Cs")) {
hysteresisStartSlider.setValue(getValueOfToken(statusToken, 2));
}
else if (statusToken.startsWith("Ce")) {
hysteresisEndSlider.setValue(getValueOfToken(statusToken, 2));
}
else if (statusToken.startsWith("Cd")) {
setHystDecrement(getValueOfToken(statusToken, 2));
}
else if ("Ke+".equals(statusToken)) {
coolStepActiveToggle.setValue(1);
}
else if ("Ke-".equals(statusToken)) {
coolStepActiveToggle.setValue(0);
}
else if (statusToken.startsWith("Kl")) {
coolStepMinSlider.setValue(getValueOfToken(statusToken, 2));
}
else if (statusToken.startsWith("Ku")) {
coolStepMaxSlider.setValue(getValueOfToken(statusToken, 2));
}
else if (statusToken.startsWith("Kn")) {
coolStepDecrementButtons.activate(getValueOfToken(statusToken, 2));
}
else if (statusToken.startsWith("Ki")) {
coolStepIncrementButtons.activate(getValueOfToken(statusToken, 2));
}
else if (statusToken.startsWith("Km")) {
coolStepMinButtons.activate(getValueOfToken(statusToken, 2));
}
}
}
else {
println(line);
}
settingStatus=false;
}
int getValueOfToken(String token, int position) {
String value = token.substring(position);
try {
return Integer.valueOf(value);
}
catch (NumberFormatException e) {
println("Unable to decode '"+value+"'of '"+token+"' !");
return 0;
}
}
void drawSerial() {
//draw the logo and some epxlaining text while setting up the serial port
if (!motor_connected) {
image(TMCLogo,200, 100);
fill(uiTextColor);
text("Select the serial port where your Arduino is connected\nIf in doubt check it in the Arduino IDE.\nThe Motor Tester will automatically verify if it can find an Motor tester ath the port.",200,100+TMCLogo.height+50);
}
}
void help(float value) {
if (value!=0) {
link(helpUrl);
}
}

View file

@ -0,0 +1,175 @@
/*
TMC26XMotorTest.pde - - TMC26X Stepper Tester for Processing
Copyright (c) 2011, Interactive Matter, Marcus Nowotny
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
Slider constantOffSlider;
Slider blankTimeSlider;
Toggle randomOffTimeToggle;
RadioButton ChopperModeButtons;
//for constant off time chopeer
Slider fastDecaySlider;
Slider sineWaveOffsetSlider;
Toggle currentComparatorToggle;
//for spread chopper
Slider hysteresisStartSlider;
Slider hysteresisEndSlider;
Numberbox motorVoltageBox;
Numberbox motorCurrentBox;
Numberbox motorResistanceBox;
Numberbox motorInductanceBox;
RadioButton hysteresisDecrementButtons;
PImage spreadChopperImage;
void setupChooperConfig() {
//add input fields for the various motor parameters
motorVoltageBox = controlP5.addNumberbox("motorvoltage",12.0,20,40,100,20);
motorVoltageBox.setCaptionLabel("Motor Voltage (V)");
motorVoltageBox.setMultiplier(0.025);
motorVoltageBox.setMin(0);
motorVoltageBox.setMax(40.0);
motorVoltageBox.moveTo(configureTab);
motorCurrentBox = controlP5.addNumberbox("motorcurrent",0.5,140,40,100,20);
motorCurrentBox.setCaptionLabel("Motor Current (A)");
motorCurrentBox.setMultiplier(0.025);
motorCurrentBox.setMin(0.46);
motorCurrentBox.setMax(1.7);
motorCurrentBox.moveTo(configureTab);
motorResistanceBox = controlP5.addNumberbox("motorresistance",2,260,40,100,20);
motorResistanceBox.setCaptionLabel("Motor Resistance (Ohm)");
motorResistanceBox.setMultiplier(0.1);
motorResistanceBox.setMin(0);
motorResistanceBox.setMax(250);
motorResistanceBox.moveTo(configureTab);
motorInductanceBox = controlP5.addNumberbox("motorinductance",2,380,40,100,20);
motorInductanceBox.setMultiplier(0.1);
motorInductanceBox.setMin(0);
motorInductanceBox.setMax(250);
motorInductanceBox.setCaptionLabel("Motor Inductance (mH)");
motorInductanceBox.moveTo(configureTab);
// add a vertical slider for speed
constantOffSlider = controlP5.addSlider("constantoff", 1, 15, 1, 20, 80, 400, 20);
constantOffSlider.setCaptionLabel("Constant Off Time");
constantOffSlider.setSliderMode(Slider.FIX);
constantOffSlider.moveTo(configureTab);
blankTimeSlider = controlP5.addSlider("blanktime", 0, 3, 2, 20, 120, 400, 20);
blankTimeSlider.setCaptionLabel("Blank Time");
blankTimeSlider.moveTo(configureTab);
hysteresisStartSlider = controlP5.addSlider("hysteresisstart", 0, 8, 2, 20, 160, 400, 20);
hysteresisStartSlider.setCaptionLabel("Hysteresis Start");
hysteresisStartSlider.moveTo(configureTab);
hysteresisEndSlider = controlP5.addSlider("hysteresisend", -3, 12, 2, 20, 200, 400, 20);
hysteresisEndSlider.setCaptionLabel("Hysteresis End");
hysteresisEndSlider.moveTo(configureTab);
hysteresisDecrementButtons =controlP5.addRadioButton("decrement", 20, 240);
hysteresisDecrementButtons.addItem("fastest", 0);
hysteresisDecrementButtons.addItem("fast", 1);
hysteresisDecrementButtons.addItem("medium", 2);
hysteresisDecrementButtons.addItem("slow", 3);
hysteresisDecrementButtons.showBar();
hysteresisDecrementButtons.moveTo(configureTab);
spreadChopperImage = loadImage("hysteresis.png");
}
void drawChopper() {
if (activeTab!=null && configureTab.equals(activeTab)) {
image(spreadChopperImage, 200, 400);
}
}
void constantoff(int theValue) {
if (!settingStatus) {
if (theValue>0 && theValue<16) {
println("Constant off "+theValue);
sendCommand("cO"+theValue);
}
else {
println("invalid blank time of "+theValue);
}
}
}
void blanktime(int theValue) {
if (!settingStatus) {
if (theValue>=0 && theValue<=3) {
println("blank time "+theValue);
sendCommand("Cb"+theValue);
}
}
}
void hysteresisstart(int start) {
if (!settingStatus) {
if (start>=1 && start<=8) {
println("hystereis start "+start);
sendCommand("Cs"+start);
}
}
}
void hysteresisend(int end) {
if (!settingStatus) {
if (end>=-3 && end<=12) {
println("hystereis end "+end);
sendCommand("Ce"+end);
}
}
}
void setHysteresisDecrement(int theValue) {
if (!settingStatus) {
if (theValue>=0 && theValue<=3) {
println("Hysteresis decrement "+theValue);
sendCommand("Cd"+theValue);
}
else {
println("cannot set decrement to "+theValue);
}
}
}
void setHystDecrement(int value) {
if (value>=0 && value<=3) {
hysteresisDecrementButtons.activate(value);
}
else {
println("this is no proper hysteresis decerement value: "+value);
}
}
void motorcurrent(float value) {
if (activeTab!=null && "default".equals(activeTab.name())) {
currentSlider.setValue(value);
}
}

View file

@ -0,0 +1,327 @@
/*
TMC26XMotorTest.pde - - TMC26X Stepper Tester for Processing
Copyright (c) 2011, Interactive Matter, Marcus Nowotny
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
//our graph dimensions
int plotBottom, plotTop;
int plotLeft, plotRight;
//we already know the minima and maxima of certain dates
int stallGuardMin = 0;
int stallGuardMax =1024;
int positionMin = 0;
int positionMax = 1024;
int dataPointsWidth = 3;
int dataLineWidth = 2;
int highLightWidth = 7;
int numberOfDataPoints=1000;
int legendTitleSize = 10;
int legendTextSize = 10;
int currentLabelInterval = 500;
int currentMinorTickInterval = 25;
DecimalFormat currentLabelFormat = new DecimalFormat("#0.0A");
int stallGuardLabelInterval = 100;
int stallGuardMinorTickInterval = 10;
int positionLabelInterval = 64;
int positionMinorTickInterval = 8;
int coolStepActiveStroke = 2;
int coolStepInactiveStroke = 1;
int stallGuardHighLightDistance = 1;
int positionHighLightDistance = 3;
int currentHighLightDistance = 3;
DataTable stallGuardTable = new DataTable(numberOfDataPoints);
DataTable positionTable = new DataTable(numberOfDataPoints);
DataTable currentTable = new DataTable(numberOfDataPoints);
int logoLeft = 10;
int logoTop = 50;
int logoWidth = 75;
int logoHeight = 75;
void setupData() {
plotBottom = height-50;
plotTop = 300;
plotLeft = 150;
plotRight= width-50;
//recalculate the image dimension for the Logo
logoHeight = (int)((float)logoWidth/(float)TMCLogo.width*(float)TMCLogo.height);
logoTop = height - 10 - logoHeight;
}
void drawData() {
if (motor_connected && activeTab!=null && runTab.equals(activeTab)) {
fill(diagramBackgroundColor);
noStroke();
rect(plotLeft, plotTop, plotRight, plotBottom);
noFill();
rectMode(CORNERS);
noStroke();
//rect(plotLeft, plotBottom, plotRight, plotTop);
strokeWeight(dataLineWidth);
stroke(positionColor);
drawDataLine(positionTable, positionMin, positionMax);
drawDataHighLight(positionTable, positionMin, positionMax, positionHighLightDistance, labelColor, "Microstep Position", false);
strokeWeight(dataLineWidth);
stroke(coolStepColor);
drawCurrentLine(currentTable);
drawCurrentHighLight(positionTable, currentHighLightDistance, labelColor, "Current Ratio", false);
strokeWeight(dataPointsWidth);
stroke(stallGuardColor);
drawDataPoints(stallGuardTable, stallGuardMin, stallGuardMax);
drawDataHighLight(stallGuardTable, stallGuardMin, stallGuardMax, stallGuardHighLightDistance, labelColor, "Stall Guard", true);
if (coolStepActive) {
strokeWeight(coolStepActiveStroke);
} else {
strokeWeight(coolStepInactiveStroke);
}
stroke(coolStepColor);
float coolStepMinHeight = map(coolStepMin, 0, stallGuardMax, plotBottom, plotTop);
line(plotLeft,coolStepMinHeight, plotRight, coolStepMinHeight);
float coolStepMaxHeight = map(coolStepMin+coolStepMax+1, 0, stallGuardMax, plotBottom, plotTop);
line(plotLeft,coolStepMaxHeight, plotRight, coolStepMaxHeight);
textSize(legendTitleSize);
textAlign(RIGHT);
fill(coolStepColor);
text("Motor Current", plotLeft - 50, plotTop - 10);
textSize(legendTextSize);
textAlign(RIGHT);
strokeWeight(1);
stroke(coolStepColor);
int currentScaleMax = (int)(maxCurrent*1000.0);
for (int i=0; i<=currentScaleMax; i++) {
float y = map(i, 0, currentScaleMax, plotBottom, plotTop);
if (i % currentLabelInterval == 0) {
if (i==0) {
textAlign(RIGHT, BOTTOM);
}
else if (i==currentScaleMax) {
textAlign(RIGHT, TOP);
}
else {
textAlign(RIGHT, CENTER);
}
text(currentLabelFormat.format((float)i/1000.0), plotLeft-58, y);
line (plotLeft-55, y, plotLeft-50, y);
}
else if (i % currentMinorTickInterval == 0) {
line (plotLeft-53, y, plotLeft-50, y);
}
}
textSize(legendTitleSize);
textAlign(LEFT);
fill(stallGuardColor);
text("Stall Guard Reading", plotLeft - 30, plotTop - 10);
textSize(legendTextSize);
textAlign(RIGHT);
strokeWeight(1);
stroke(stallGuardColor);
for (int i=stallGuardMin; i<=stallGuardMax; i++) {
float y = map(i, stallGuardMin, stallGuardMax, plotBottom, plotTop);
if (i % stallGuardLabelInterval == 0) {
if (i==stallGuardMin) {
textAlign(RIGHT, BOTTOM);
}
else if (i==stallGuardMax) {
textAlign(RIGHT, TOP);
}
else {
textAlign(RIGHT, CENTER);
}
text(i, plotLeft-8, y);
line (plotLeft-5, y, plotLeft, y);
}
else if (i % stallGuardMinorTickInterval == 0) {
line (plotLeft-3, y, plotLeft, y);
}
}
textSize(legendTitleSize);
fill(positionColor);
textAlign(RIGHT);
text("Position", plotRight + 30, plotTop - 10);
textSize(legendTextSize);
textAlign(LEFT);
strokeWeight(1);
stroke(positionColor);
for (int i=positionMin; i<=positionMax; i++) {
float y = map(i, positionMin, positionMax, plotBottom, plotTop);
if (i % positionLabelInterval == 0) {
if (i==positionMin) {
textAlign(LEFT, BOTTOM);
}
else if (i==stallGuardMax) {
textAlign(LEFT, TOP);
}
else {
textAlign(LEFT, CENTER);
}
text(i, plotRight+8, y);
line (plotRight, y, plotRight+5, y);
}
else if (i % positionMinorTickInterval == 0) {
line (plotRight, y, plotRight+3, y);
}
}
//draw the channel status
textSize(legendTextSize);
textAlign(CENTER);
strokeWeight(1);
int statusY = height - 20;
int channelAX = width/4;
int temperatureX = width/2;
int channelBX = width/4*3;
if (channelAStatus==null) {
fill(goodStatusColor);
text("Channel A: OK", channelAX, statusY);
}
else {
fill(badStatusColor);
text("Channel A: "+channelAStatus, channelAX, statusY);
}
if (channelBStatus==null) {
fill(goodStatusColor);
text("Channel B: OK", channelBX, statusY);
}
else {
fill(badStatusColor);
text("Channel B: "+channelBStatus, channelBX, statusY);
}
if (temperatureStatus==null) {
fill(goodStatusColor);
text("Temperature: OK", temperatureX, statusY);
}
else {
fill(badStatusColor);
text("Temperature: "+temperatureStatus, temperatureX, statusY);
}
}
}
void drawDataPoints(DataTable table, int minValue, int maxValue) {
int dataCount = table.getSize();
for (int i=0; i<dataCount; i++) {
int value = table.getEntry(i);
float x = map(i, 0, numberOfDataPoints-1, plotLeft+dataPointsWidth, plotRight-dataPointsWidth);
float y = map(value, minValue, maxValue, plotBottom-dataPointsWidth, plotTop+dataPointsWidth);
point(x, y);
}
}
void drawDataLine(DataTable table, int minValue, int maxValue) {
beginShape();
int dataCount = table.getSize();
for (int i=0; i<dataCount; i++) {
int value = table.getEntry(i);
float x = map(i, 0, numberOfDataPoints-1, plotLeft+dataPointsWidth, plotRight-dataPointsWidth);
float y = map(value, minValue, maxValue, plotBottom-dataPointsWidth, plotTop+dataPointsWidth);
vertex(x, y);
}
endShape();
}
void drawDataHighLight(DataTable table, int minValue, int maxValue, int distance, color textColor, String name, boolean top) {
int dataCount = table.getSize();
for (int i=0; i<dataCount; i++) {
int value = table.getEntry(i);
float x = map(i, 0, numberOfDataPoints-1, plotLeft+dataPointsWidth, plotRight-dataPointsWidth);
float y = map(value, minValue, maxValue, plotBottom-dataPointsWidth, plotTop+dataPointsWidth);
if (dist(mouseX, mouseY, x, y) < distance) {
strokeWeight(highLightWidth);
point(x, y);
fill(textColor);
textSize(10);
textAlign(CENTER);
if (top) {
text(name+": "+value, x, y-8);
}
else {
text(name+": "+value, x, y+8);
}
}
}
}
void drawCurrentLine(DataTable table) {
noFill();
beginShape();
int dataCount = table.getSize();
for (int i=0; i<dataCount; i++) {
float value = (table.getEntry(i)+1)/1000.0;
float x = map(i, 0, numberOfDataPoints-1, plotLeft+dataPointsWidth, plotRight-dataPointsWidth);
float y = map(value, 0.0, maxCurrent, (float)plotBottom-dataPointsWidth, (float)plotTop+dataPointsWidth);
vertex(x, y);
}
endShape();
}
void drawCurrentHighLight(DataTable table, int distance, color textColor, String name, boolean top) {
int dataCount = table.getSize();
for (int i=0; i<dataCount; i++) {
float value = (table.getEntry(i)+1)/1000.0;
float x = map(i, 0, numberOfDataPoints-1, plotLeft+dataPointsWidth, plotRight-dataPointsWidth);
float y = map(value, 0.0, maxCurrent, plotBottom-dataPointsWidth, plotTop+dataPointsWidth);
if (dist(mouseX, mouseY, x, y) < distance) {
strokeWeight(highLightWidth);
point(x, y);
fill(textColor);
textSize(10);
textAlign(CENTER);
if (top) {
text(name+": "+value, x, y-8);
}
else {
text(name+": "+value, x, y+8);
}
}
}
}
void addStallGuardReading(int value) {
stallGuardTable.addData(value);
}
void addPositionReading(int value) {
positionTable.addData(value);
}
void addCurrentReading(int value) {
currentTable.addData(value);
}

View file

@ -0,0 +1,49 @@
/*
TMC26XMotorTest.pde - - TMC26X Stepper Tester for Processing
Copyright (c) 2011, Interactive Matter, Marcus Nowotny
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
class DataTable {
LinkedList<Integer> dataList = new LinkedList<Integer>();
int maxEntries;
DataTable(int maxEntries) {
this.maxEntries = maxEntries;
}
void addData(int value) {
dataList.add(value);
if (dataList.size()>maxEntries) {
dataList.remove();
}
}
int getSize() {
return dataList.size();
}
int getEntry(int position) {
return dataList.get(position);
}
}

View file

@ -0,0 +1,335 @@
/*
TMC26XMotorTest.pde - - TMC26X Stepper Tester for Processing
Copyright (c) 2011, Interactive Matter, Marcus Nowotny
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
Slider speedSlider;
Toggle runToggle;
RadioButton directionButtons;
Toggle enabledToggle;
RadioButton microsteppingButtons;
Slider sgtSlider;
Button sgtPlus;
Button sgtMinus;
Toggle sgFilterToggle;
Slider currentSlider;
Slider coolStepMinSlider;
Slider coolStepMaxSlider;
Toggle coolStepActiveToggle;
RadioButton coolStepIncrementButtons;
RadioButton coolStepDecrementButtons;
RadioButton coolStepMinButtons;
List runControls = new LinkedList();
Button trinamicButton;
Button motionControlButton;
void setupRunConfig() {
//the run configuration
//controlP5.getControlFont().setSize(10); - the font is too small, try to increase it!
//add a button te let the motor run
runToggle = controlP5.addToggle("run", false, 20, 40, 30, 30);
controlElements.add(runToggle);
runToggle.moveTo(runTab);
//add some directions buttons
directionButtons = controlP5.addRadioButton("direction", 20, 90);
controlElements.add(directionButtons);
directionButtons.addItem("forward", 1);
directionButtons.addItem("backward", -1);
directionButtons.activate(0);
directionButtons.moveTo(runTab);
enabledToggle = controlP5.addToggle("enabled", false, 20, 220, 30, 30);
controlElements.add(enabledToggle);
enabledToggle.moveTo(runTab);
// add a vertical slider for speed
speedSlider = controlP5.addSlider("speed", 1, 100, 10, 85, 40, 20, 210);
controlElements.add(speedSlider);
speedSlider.moveTo(runTab);
//ad a multilist for the microstepping setting
microsteppingButtons = controlP5.addRadioButton("microstepping", 150, 40);
controlElements.add(microsteppingButtons);
microsteppingButtons.addItem("m_1/1", 1);
microsteppingButtons.addItem("m_1/2", 2);
microsteppingButtons.addItem("m_1/4", 4);
microsteppingButtons.addItem("m_1/8", 8);
microsteppingButtons.addItem("m_1/16", 16);
microsteppingButtons.addItem("m_1/32", 32);
microsteppingButtons.addItem("m_1/64", 64);
microsteppingButtons.addItem("m_1/128", 128);
microsteppingButtons.addItem("m_1/256", 256);
for (Object o:microsteppingButtons.getItems()) {
Toggle t = (Toggle) o;
t.setCaptionLabel(t.getName().substring(2));
}
microsteppingButtons.showBar();
microsteppingButtons.moveTo(runTab);
currentSlider = controlP5.addSlider("current", 0.46, maxCurrent, 0.4, 250, 40, 20, 210);
controlElements.add(currentSlider);
currentSlider.moveTo(runTab);
// add a vertical slider for stallGuard threshold
sgtPlus = controlP5.addButton("sgtplus", 0, 400, 40, 20, 20);
controlElements.add(sgtPlus);
sgtPlus.setCaptionLabel("+");
sgtPlus.moveTo(runTab);
sgtMinus = controlP5.addButton("sgtminus", 1, 400, 70, 20, 20);
controlElements.add(sgtMinus);
sgtMinus.setCaptionLabel("-");
sgtMinus.moveTo(runTab);
sgtSlider = controlP5.addSlider("stallguardthreshold", -64, 63, 0, 350, 40, 20, 150);
controlElements.add(sgtSlider);
sgtSlider.setSliderMode(Slider.FIX);
sgtSlider.setCaptionLabel("Stall Guard Threshold");
sgtSlider.moveTo(runTab);
//ading some buttons to have finer sg control
//adding a button for the filter
sgFilterToggle = controlP5.addToggle("sgfilter", false, 350, 220, 30, 30);
controlElements.add(sgFilterToggle);
sgFilterToggle.setCaptionLabel("Stall GuardFilter");
sgFilterToggle.moveTo(runTab);
//add the coolstep sliders
coolStepMaxSlider = controlP5.addSlider("coolStepUpper", 0, 480, 0, 500, 40, 20, 90);
controlElements.add(coolStepMaxSlider);
coolStepMaxSlider.setCaptionLabel("Cool Step Hysteresis");
coolStepMaxSlider.moveTo(runTab);
coolStepMinSlider = controlP5.addSlider("coolStepLower", 0, 480, 0, 500, 160, 20, 90);
controlElements.add(coolStepMinSlider);
coolStepMinSlider.setCaptionLabel("Cool Step Minimum");
coolStepMinSlider.moveTo(runTab);
coolStepActiveToggle = controlP5.addToggle("coolStepActive", false, 600, 220, 30, 30);
controlElements.add(coolStepActiveToggle);
coolStepActiveToggle.setCaptionLabel("Enable CoolStep");
coolStepActiveToggle.moveTo(runTab);
coolStepIncrementButtons = controlP5.addRadioButton("coolStepIncrement", 600, 40);
controlElements.add(coolStepIncrementButtons);
coolStepIncrementButtons.captionLabel().set("Cool Step Increment");
coolStepIncrementButtons.addItem("i_1", 0);
coolStepIncrementButtons.addItem("i_2", 1);
coolStepIncrementButtons.addItem("i_4", 2);
coolStepIncrementButtons.addItem("i_8", 3);
for (Object o:coolStepIncrementButtons.getItems()) {
Toggle t = (Toggle) o;
t.setCaptionLabel(t.getName().substring(2));
}
coolStepIncrementButtons.showBar();
coolStepIncrementButtons.moveTo(runTab);
coolStepDecrementButtons = controlP5.addRadioButton("coolStepDecrement", 600, 110);
controlElements.add(coolStepDecrementButtons);
coolStepDecrementButtons.captionLabel().set("Cool Step Decrement");
coolStepDecrementButtons.addItem("d_32", 0);
coolStepDecrementButtons.addItem("d_8", 1);
coolStepDecrementButtons.addItem("d_2", 2);
coolStepDecrementButtons.addItem("d_1", 3);
for (Object o:coolStepDecrementButtons.getItems()) {
Toggle t = (Toggle) o;
t.setCaptionLabel(t.getName().substring(2));
}
coolStepDecrementButtons.showBar();
coolStepDecrementButtons.moveTo(runTab);
coolStepMinButtons = controlP5.addRadioButton("coolStepMin", 600, 180);
controlElements.add(coolStepMinButtons);
coolStepMinButtons.addItem("s_1/2", 0);
coolStepMinButtons.addItem("s_1/4", 1);
for (Object o:coolStepMinButtons.getItems()) {
Toggle t = (Toggle) o;
t.setCaptionLabel(t.getName().substring(2));
}
coolStepMinButtons.showBar();
coolStepMinButtons.moveTo(runTab);
trinamicButton = controlP5.addButton("trinamicLogo", 1.0, 750, 40, 200, 100);
trinamicButton.setImage(TMCLogo);
trinamicButton.moveTo(runTab);
controlElements.add(trinamicButton);
motionControlButton = controlP5.addButton("mcLogo", 1.0, 750, 150, 200, 100);
motionControlButton.setImage(MCLogo);
motionControlButton.moveTo(runTab);
controlElements.add(motionControlButton);
}
void speed(int theSpeed) {
if (!settingStatus) {
int speed = (int) theSpeed;
println("setting speed to "+speed);
sendCommand("S"+speed);
}
}
void run(int value) {
if (!settingStatus) {
println("button pressed");
if (running) {
println("stopping motor");
sendCommand("s");
running = false;
}
else {
println("starting motor");
sendCommand("r");
running = true;
}
}
}
void enabled(int value) {
if (!settingStatus) {
println("enabled: "+value);
sendCommand("e"+value);
}
}
void microstepping(int value) {
if (!settingStatus) {
println("microstepping: "+value);
sendCommand("m"+value);
}
}
void stallguardthreshold(int value) {
if (!settingStatus) {
println("stall guard threshold: "+value);
sendCommand("t"+value);
}
if (value==sgtSlider.max()) {
sgtPlus.lock();
}
else {
sgtPlus.unlock();
}
if (value==sgtSlider.min()) {
sgtMinus.lock();
}
else {
sgtMinus.unlock();
}
}
void sgtplus(int value) {
sgtSlider.setValue(sgtSlider.value()+1);
}
void sgtminus(int value) {
sgtSlider.setValue(sgtSlider.value()-1);
}
void sgfilter(int value) {
if (!settingStatus) {
println("filter: "+value);
sendCommand("f"+value);
}
}
void current(float value) {
if (!settingStatus) {
int realValue=(int)(value*1000.0);
println("current: "+((float)realValue/1000.0)+" = "+realValue);
sendCommand("c"+realValue);
if (activeTab!=null && "run".equals(activeTab.name())) {
motorCurrentBox.setValue(value);
}
}
}
void coolStepUpper(int value) {
coolStepMax=value;
if (!settingStatus) {
sendCommand("Ku"+value);
}
}
void coolStepLower(int value) {
coolStepMin = value;
if (!settingStatus) {
sendCommand("Kl"+value);
}
}
void setCoolStepIncrement(int value) {
if (!settingStatus) {
println("cool step increment :"+value);
sendCommand("Ki"+value);
}
}
void setCoolStepDecrement(int value) {
if (!settingStatus) {
println("cool step decrement :"+value);
sendCommand("Kn"+value);
}
}
void setCoolStepMin(int value) {
if (!settingStatus) {
println("cool step minimum :"+value);
sendCommand("Km"+value);
}
}
void coolStepActive(int value) {
if (!settingStatus) {
coolStepActive = (value!=0);
sendCommand(coolStepActive? "K+":"K-");
}
}
void setCurrent(int current) {
currentSlider.setValue((float)current/1000.0);
}
void setDirection(int direction) {
if (!settingStatus) {
if (direction<0) {
println("back");
sendCommand("d-1");
}
else {
sendCommand("d1");
}
}
}
void trinamicLogo(float value){
if (value!=0) {
link(trinamicUrl);
}
}
void mcLogo(float value) {
if (value!=0) {
link(mcUrl);
}
}

View file

@ -0,0 +1,156 @@
/*
TMC26XMotorTest.pde - - TMC26X Stepper Tester for Processing
Copyright (c) 2011, Interactive Matter, Marcus Nowotny
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
import controlP5.*;
import processing.serial.*;
import java.util.*;
import java.text.*;
ControlP5 controlP5;
Serial arduinoPort;
String helpUrl = "http://www.motioncontrol-community.org/";
String trinamicUrl = "http://trinamic.com";
String mcUrl = "http://www.motioncontrol-community.org/";
//TODO comde up with a nice color scheme
color activeColor = #01ADF1;
color foreGroundColor = #01ADF1;
color uiTextColor = #4D4D4F;
color uiElementColor = #ffffff;
color labelColor = #f0f0f0;
color valueColor = #f0f0f0;
color backgroundColor = #EDEEEF;
color stallGuardColor = #969696;
color positionColor = #01ADF1;
color goodStatusColor = labelColor;
color badStatusColor = stallGuardColor;
color coolStepColor = #4D4D4F;
color diagramBackgroundColor = #ffffff;
CColor uiColor = new CColor( foreGroundColor, uiElementColor, activeColor, uiTextColor, uiTextColor);
Tab configureTab;
Tab runTab;
Tab activeTab;
boolean settingStatus=false;
boolean running = false;
int coolStepMin = 0;
int coolStepMax = 0;
boolean coolStepActive = false;
float maxCurrent = 1.7;
List controlElements = new LinkedList();
List serialConfigElements = new LinkedList();
PImage TMCLogo;
PImage MCLogo;
void setup() {
size(1000, 800);
//load the logos
TMCLogo=loadImage("tmc_logo.jpg");
MCLogo=loadImage("mc_logo.jpg");
//create the UI
controlP5 = new ControlP5(this);
controlP5.setColor(uiColor);
runTab = controlP5.getTab("default");
configureTab =controlP5.addTab("configure");
//customize the tabs a bit
configureTab.setLabel("configure");
controlElements.add(configureTab);
activeTab = controlP5.getTab("default");
controlP5.setTabEventsActive(true);
configureTab.activateEvent(true);
runTab.activateEvent(true);
//configuring the general UI l&f
//the configuration UI
setupRunConfig();
setupChooperConfig();
setupSerialConfig();
//directly hide the controls again since we are not connected to the Arduino yet
toggleUi(motor_connected);
smooth();
setupData();
}
void toggleUi(boolean show_controls) {
for (Object c:controlElements) {
ControllerInterface controller = (ControllerInterface) c;
if (show_controls) {
controller.show();
} else {
controller.hide();
}
}
for (Object c:serialConfigElements) {
ControllerInterface controller = (ControllerInterface) c;
if (show_controls) {
controller.hide();
} else {
controller.show();
}
}
}
void draw() {
background(backgroundColor);
drawSerial();
drawChopper();
drawData();
decodeSerial();
}
void controlEvent(ControlEvent theEvent) {
if (theEvent.isGroup() && !settingStatus) {
if ("microstepping".equals(theEvent.group().name())) {
microstepping((int)theEvent.group().value());
} else
if ("direction".equals(theEvent.group().name())) {
setDirection((int)theEvent.group().value());
} else if ("decrement".equals(theEvent.group().name())) {
setHysteresisDecrement((int)theEvent.group().value());
} else if ("coolStepIncrement".equals(theEvent.group().name())) {
setCoolStepIncrement((int)theEvent.group().value());
} else if ("coolStepDecrement".equals(theEvent.group().name())) {
setCoolStepDecrement((int)theEvent.group().value());
} else if ("coolStepMin".equals(theEvent.group().name())) {
setCoolStepMin((int)theEvent.group().value());
}
}
else if (theEvent.isTab()) {
activeTab = theEvent.tab();
println("Tab: "+activeTab.name());
}
}

View file

@ -0,0 +1,2 @@
mode.id=processing.mode.java.JavaMode
mode=Java

View file

@ -0,0 +1,75 @@
#######################################
# Syntax Coloring Map For Test
#######################################
#######################################
# Datatypes (KEYWORD1)
#######################################
Stepper TMC26XStepper
#######################################
# Methods and Functions (KEYWORD2)
#######################################
start KEYWORD2
step KEYWORD2
setSpeed KEYWORD2
getSpeed KEYWORD2
setMicrosteps KEYWORD2
getMicrosteps KEYWORD2
move KEYWORD2
isMoving KEYWORD2
getStepsLeft KEYWORD2
stop KEYWORD2
setConstantOffTimeChopper KEYWORD2
setSpreadCycleChopper KEYWORD2
setRandomOffTime KEYWORD2
setCurrent KEYWORD2
getCurrent KEYWORD2
setStallGuardThreshold KEYWORD2
getStallGuardThreshold KEYWORD2
getStallGuardFilter KEYWORD2
setCoolStepConfiguration KEYWORD2
setCoolStepEnabled KEYWORD2
isCoolStepEnabled KEYWORD2
getCoolStepLowerSgThreshold KEYWORD2
getCoolStepUpperSgThreshold KEYWORD2
getCoolStepNumberOfSGReadings KEYWORD2
getCoolStepCurrentIncrementSize KEYWORD2
getCoolStepLowerCurrentLimit KEYWORD2
getMotorPosition KEYWORD2
getCurrentStallGuardReading KEYWORD2
getCurrentCSReading KEYWORD2
isCurrentScalingHalfed KEYWORD2
getCurrentCurrent KEYWORD2
isStallGuardOverThreshold KEYWORD2
getOverTemperature KEYWORD2
isShortToGroundA KEYWORD2
isShortToGroundB KEYWORD2
isOpenLoadA KEYWORD2
isOpenLoadB KEYWORD2
isStandStill KEYWORD2
isStallGuardReached KEYWORD2
setEnabled KEYWORD2
isEnabled KEYWORD2
readStatus KEYWORD2
getResistor KEYWORD2
debugLastStatus KEYWORD2
version KEYWORD2
######################################
# Instances (KEYWORD2)
#######################################
#######################################
# Constants (LITERAL1)
#######################################
TMC262_OVERTEMPERATURE_PREWARING LITERAL1
TMC262_OVERTEMPERATURE_SHUTDOWN LITERAL1
TMC262_READOUT_POSITION LITERAL1
TMC262_READOUT_STALLGUARD LITERAL1
TMC262_READOUT_CURRENT LITERAL1
COOL_STEP_HALF_CS_LIMIT LITERAL1
COOL_STEP_QUARTDER_CS_LIMIT LITERAL1

View file

@ -0,0 +1,30 @@
/*!
* \mainpage TMC 260, 261, 262 Stepper Driver for Arduino
* \author Interactive MAtter, MArcus Nowotny, marcus@interactive-matter.eu
* \section HOWTO How to use the driver
* Here we go with aminial how to description
*
*
* \section COPYRIGHT_NOTIFICATION COPYRIGHT NOTIFICATION
* \par (c) 2011 Interactive MAtter, Marcus Nowotny
*
* \par
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
*/

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

View file

@ -101,3 +101,25 @@
* M908 - Control digital trimpot directly.
* M928 - Start SD logging (M928 filename.g) - ended by M29
* M999 - Restart after being stopped by error
# Comments
Comments start at a `;` (semicolon) and end with the end of the line:
N3 T0*57 ; This is a comment
N4 G92 E0*67
; So is this
N5 G28*22
(example taken from the [RepRap wiki](http://reprap.org/wiki/Gcode#Comments))
If you need to use a literal `;` somewhere (for example within `M117`), you can escape semicolons with a `\`
(backslash):
M117 Hello \;)
`\` can also be used to escape `\` itself, if you need a literal `\` in front of a `;`:
M117 backslash: \\;and a comment
Please note that hosts should strip any comments before sending GCODE to the printer in order to save bandwidth.

View file

@ -0,0 +1 @@

View file

@ -8,7 +8,7 @@
//===========================================================================
/*
Here are some standard links for getting your machine calibrated:
* http://reprap.org/wiki/Calibration
* http://reprap.org/wiki/Calibration
* http://youtu.be/wAL9d7FgInk
* http://calculator.josefprusa.cz
* http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
@ -59,7 +59,7 @@ Here are some standard links for getting your machine calibrated:
// The following define selects which electronics board you have.
// Please choose the name from boards.h that matches your setup
#ifndef MOTHERBOARD
#define MOTHERBOARD BOARD_ULTIMAKER
#define MOTHERBOARD BOARD_RAMPS_13_EFB
#endif
// Define this to set a custom name for your generic Mendel,
@ -123,8 +123,8 @@ Here are some standard links for getting your machine calibrated:
// #define DUMMY_THERMISTOR_998_VALUE 25
// #define DUMMY_THERMISTOR_999_VALUE 100
#define TEMP_SENSOR_0 -1
#define TEMP_SENSOR_1 -1
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 0
@ -295,38 +295,27 @@ your extruder heater takes 2 minutes to hit the target on heating.
//============================= Mechanical Settings =========================
//===========================================================================
// Uncomment the following line to enable CoreXY kinematics
// Uncomment this option to enable CoreXY kinematics
// #define COREXY
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
// Enable this option for Toshiba steppers
// #define CONFIG_STEPPERS_TOSHIBA
#ifndef ENDSTOPPULLUPS
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
// #define ENDSTOPPULLUP_XMAX
// #define ENDSTOPPULLUP_YMAX
// #define ENDSTOPPULLUP_ZMAX
// #define ENDSTOPPULLUP_XMIN
// #define ENDSTOPPULLUP_YMIN
// #define ENDSTOPPULLUP_ZMIN
#endif
// The pullups are needed if you directly connect a mechanical endstop between the signal and ground pins.
#define ENDSTOPPULLUP_XMAX
#define ENDSTOPPULLUP_YMAX
#define ENDSTOPPULLUP_ZMAX
#define ENDSTOPPULLUP_XMIN
#define ENDSTOPPULLUP_YMIN
#define ENDSTOPPULLUP_ZMIN
#ifdef ENDSTOPPULLUPS
#define ENDSTOPPULLUP_XMAX
#define ENDSTOPPULLUP_YMAX
#define ENDSTOPPULLUP_ZMAX
#define ENDSTOPPULLUP_XMIN
#define ENDSTOPPULLUP_YMIN
#define ENDSTOPPULLUP_ZMIN
#endif
// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
const bool X_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
//#define DISABLE_MAX_ENDSTOPS
//#define DISABLE_MIN_ENDSTOPS
@ -343,13 +332,14 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DISABLE_E false // For all extruders
#define DISABLE_INACTIVE_EXTRUDER true //disable only inactive extruders and keep active extruder enabled
#define INVERT_X_DIR true // for Mendel set to false, for Orca set to true
#define INVERT_Y_DIR false // for Mendel set to true, for Orca set to false
#define INVERT_Z_DIR true // for Mendel set to false, for Orca set to true
#define INVERT_E0_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
#define INVERT_E1_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
#define INVERT_E2_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
#define INVERT_E3_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
// If you motor turns to wrong direction, you can invert it here:
#define INVERT_X_DIR false
#define INVERT_Y_DIR false
#define INVERT_Z_DIR false
#define INVERT_E0_DIR false
#define INVERT_E1_DIR false
#define INVERT_E2_DIR false
#define INVERT_E3_DIR false
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
@ -361,9 +351,9 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define max_software_endstops true // If true, axis won't move to coordinates greater than the defined lengths below.
// Travel limits after homing (units are in mm)
#define X_MAX_POS 205
#define X_MAX_POS 200
#define X_MIN_POS 0
#define Y_MAX_POS 205
#define Y_MAX_POS 200
#define Y_MIN_POS 0
#define Z_MAX_POS 200
#define Z_MIN_POS 0
@ -382,40 +372,40 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#ifdef ENABLE_AUTO_BED_LEVELING
// There are 2 different ways to pick the X and Y locations to probe:
// - "grid" mode
// Probe every point in a rectangular grid
// You must specify the rectangle, and the density of sample points
// This mode is preferred because there are more measurements.
// It used to be called ACCURATE_BED_LEVELING but "grid" is more descriptive
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You must specify the X & Y coordinates of all 3 points
// There are 2 different ways to specify probing locations
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You specify the XY coordinates of all 3 points.
// Enable this to sample the bed in a grid (least squares solution)
// Note: this feature generates 10KB extra code size
#define AUTO_BED_LEVELING_GRID
// with AUTO_BED_LEVELING_GRID, the bed is sampled in a
// AUTO_BED_LEVELING_GRID_POINTSxAUTO_BED_LEVELING_GRID_POINTS grid
// and least squares solution is calculated
// Note: this feature occupies 10'206 byte
#ifdef AUTO_BED_LEVELING_GRID
// set the rectangle in which to probe
// The edges of the rectangle in which to probe
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define BACK_PROBE_BED_POSITION 180
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#define MIN_PROBE_EDGE 10 // The probe square sides can be no smaller than this
// set the number of grid points per dimension
// I wouldn't see a reason to go above 3 (=9 probing points on the bed)
// Set the number of grid points per dimension
// You probably don't need more than 3 (squared=9)
#define AUTO_BED_LEVELING_GRID_POINTS 2
#else // not AUTO_BED_LEVELING_GRID
// with no grid, just probe 3 arbitrary points. A simple cross-product
// is used to esimate the plane of the print bed
#else // !AUTO_BED_LEVELING_GRID
// Arbitrary points to probe. A simple cross-product
// is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
@ -426,10 +416,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#endif // AUTO_BED_LEVELING_GRID
// these are the offsets to the probe relative to the extruder tip (Hotend - Probe)
// Offsets to the probe relative to the extruder tip (Hotend - Probe)
// X and Y offsets must be integers
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // -left +right
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // -front +behind
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // Probe on: -left +right
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Probe on: -front +behind
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // -below (always!)
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z before homing (G28) for Probe Clearance.
@ -440,6 +430,9 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define Z_RAISE_BEFORE_PROBING 15 //How much the extruder will be raised before traveling to the first probing point.
#define Z_RAISE_BETWEEN_PROBINGS 5 //How much the extruder will be raised when traveling from between next probing points
// #define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" //These commands will be executed in the end of G29 routine.
//Useful to retract a deployable probe.
//#define Z_PROBE_SLED // turn on if you have a z-probe mounted on a sled like those designed by Charles Bell
//#define SLED_DOCKING_OFFSET 5 // the extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
@ -467,29 +460,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#endif
#ifdef AUTO_BED_LEVELING_GRID // Check if Probe_Offset * Grid Points is greater than Probing Range
#if X_PROBE_OFFSET_FROM_EXTRUDER < 0
#if (-(X_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION))
#error "The X axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#else
#if ((X_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION))
#error "The X axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#endif
#if Y_PROBE_OFFSET_FROM_EXTRUDER < 0
#if (-(Y_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION))
#error "The Y axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#else
#if ((Y_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION))
#error "The Y axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#endif
#endif
#endif // ENABLE_AUTO_BED_LEVELING
@ -510,12 +480,13 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {78.7402,78.7402,200.0*8/3,760*1.1} // default steps per unit for Ultimaker
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_AXIS_STEPS_PER_UNIT {80,80,4000,500} // default steps per unit for Ultimaker
#define DEFAULT_MAX_FEEDRATE {300, 300, 5, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {3000,3000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
@ -556,11 +527,11 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// Preheat Constants
#define PLA_PREHEAT_HOTEND_TEMP 180
#define PLA_PREHEAT_HPB_TEMP 70
#define PLA_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
#define PLA_PREHEAT_FAN_SPEED 0 // Insert Value between 0 and 255
#define ABS_PREHEAT_HOTEND_TEMP 240
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
#define ABS_PREHEAT_HPB_TEMP 110
#define ABS_PREHEAT_FAN_SPEED 0 // Insert Value between 0 and 255
//==============================LCD and SD support=============================

View file

@ -3,7 +3,7 @@
*
* Configuration and EEPROM storage
*
* V15 EEPROM Layout:
* V16 EEPROM Layout:
*
* ver
* axis_steps_per_unit (x4)
@ -11,6 +11,7 @@
* max_acceleration_units_per_sq_second (x4)
* acceleration
* retract_acceleration
* travel_aceeleration
* minimumfeedrate
* mintravelfeedrate
* minsegmenttime
@ -104,7 +105,7 @@ void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) {
// wrong data being written to the variables.
// ALSO: always make sure the variables in the Store and retrieve sections are in the same order.
#define EEPROM_VERSION "V15"
#define EEPROM_VERSION "V16"
#ifdef EEPROM_SETTINGS
@ -118,6 +119,7 @@ void Config_StoreSettings() {
EEPROM_WRITE_VAR(i, max_acceleration_units_per_sq_second);
EEPROM_WRITE_VAR(i, acceleration);
EEPROM_WRITE_VAR(i, retract_acceleration);
EEPROM_WRITE_VAR(i, travel_acceleration);
EEPROM_WRITE_VAR(i, minimumfeedrate);
EEPROM_WRITE_VAR(i, mintravelfeedrate);
EEPROM_WRITE_VAR(i, minsegmenttime);
@ -253,6 +255,7 @@ void Config_RetrieveSettings() {
EEPROM_READ_VAR(i, acceleration);
EEPROM_READ_VAR(i, retract_acceleration);
EEPROM_READ_VAR(i, travel_acceleration);
EEPROM_READ_VAR(i, minimumfeedrate);
EEPROM_READ_VAR(i, mintravelfeedrate);
EEPROM_READ_VAR(i, minsegmenttime);
@ -380,6 +383,7 @@ void Config_ResetDefault() {
acceleration = DEFAULT_ACCELERATION;
retract_acceleration = DEFAULT_RETRACT_ACCELERATION;
travel_acceleration = DEFAULT_TRAVEL_ACCELERATION;
minimumfeedrate = DEFAULT_MINIMUMFEEDRATE;
minsegmenttime = DEFAULT_MINSEGMENTTIME;
mintravelfeedrate = DEFAULT_MINTRAVELFEEDRATE;
@ -516,11 +520,12 @@ void Config_PrintSettings(bool forReplay) {
SERIAL_EOL;
SERIAL_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Acceleration: S=acceleration, T=retract acceleration");
SERIAL_ECHOLNPGM("Accelerations: P=printing, R=retract and T=travel");
SERIAL_ECHO_START;
}
SERIAL_ECHOPAIR(" M204 S", acceleration );
SERIAL_ECHOPAIR(" T", retract_acceleration);
SERIAL_ECHOPAIR(" M204 P", acceleration );
SERIAL_ECHOPAIR(" R", retract_acceleration);
SERIAL_ECHOPAIR(" T", travel_acceleration);
SERIAL_EOL;
SERIAL_ECHO_START;

View file

@ -214,6 +214,7 @@
#define X_HOME_RETRACT_MM 5
#define Y_HOME_RETRACT_MM 5
#define Z_HOME_RETRACT_MM 2
#define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
#define AXIS_RELATIVE_MODES {false, false, false, false}
@ -461,6 +462,141 @@ const unsigned int dropsegments=5; //everything with less than this number of st
#endif
#endif
/******************************************************************************\
* enable this section if you have TMC26X motor drivers.
* you need to import the TMC26XStepper library into the arduino IDE for this
******************************************************************************/
//#define HAVE_TMCDRIVER
#ifdef HAVE_TMCDRIVER
// #define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
// #define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
// #define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
// #define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
// #define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
// #define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
// #define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
// #define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
// #define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
// #define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the arduino IDE for this
******************************************************************************/
//#define HAVE_L6470DRIVER
#ifdef HAVE_L6470DRIVER
// #define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#endif
//===========================================================================
//============================= Define Defines ============================
//===========================================================================

View file

@ -23,41 +23,41 @@
#include "pins.h"
#ifndef AT90USB
#define HardwareSerial_h // trick to disable the standard HWserial
#define HardwareSerial_h // trick to disable the standard HWserial
#endif
#if (ARDUINO >= 100)
# include "Arduino.h"
#include "Arduino.h"
#else
# include "WProgram.h"
#include "WProgram.h"
#endif
// Arduino < 1.0.0 does not define this, so we need to do it ourselves
#ifndef analogInputToDigitalPin
# define analogInputToDigitalPin(p) ((p) + 0xA0)
#define analogInputToDigitalPin(p) ((p) + 0xA0)
#endif
#ifdef AT90USB
#include "HardwareSerial.h"
#include "HardwareSerial.h"
#endif
#include "MarlinSerial.h"
#ifndef cbi
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
#endif
#ifndef sbi
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
#endif
#include "WString.h"
#ifdef AT90USB
#ifdef BTENABLED
#define MYSERIAL bt
#else
#define MYSERIAL Serial
#endif // BTENABLED
#ifdef BTENABLED
#define MYSERIAL bt
#else
#define MYSERIAL Serial
#endif // BTENABLED
#else
#define MYSERIAL MSerial
#endif
@ -86,7 +86,7 @@ extern const char echomagic[] PROGMEM;
#define SERIAL_ECHOPAIR(name,value) (serial_echopair_P(PSTR(name),(value)))
#define SERIAL_EOL SERIAL_ECHOLN("")
#define SERIAL_EOL MYSERIAL.write('\n')
void serial_echopair_P(const char *s_P, float v);
void serial_echopair_P(const char *s_P, double v);
@ -112,11 +112,11 @@ void manage_inactivity(bool ignore_stepper_queue=false);
#if defined(DUAL_X_CARRIAGE) && defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1 \
&& defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1
#define enable_x() do { WRITE(X_ENABLE_PIN, X_ENABLE_ON); WRITE(X2_ENABLE_PIN, X_ENABLE_ON); } while (0)
#define disable_x() do { WRITE(X_ENABLE_PIN,!X_ENABLE_ON); WRITE(X2_ENABLE_PIN,!X_ENABLE_ON); axis_known_position[X_AXIS] = false; } while (0)
#define enable_x() do { X_ENABLE_WRITE( X_ENABLE_ON); X2_ENABLE_WRITE( X_ENABLE_ON); } while (0)
#define disable_x() do { X_ENABLE_WRITE(!X_ENABLE_ON); X2_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; } while (0)
#elif defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1
#define enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
#define disable_x() { WRITE(X_ENABLE_PIN,!X_ENABLE_ON); axis_known_position[X_AXIS] = false; }
#define enable_x() X_ENABLE_WRITE( X_ENABLE_ON)
#define disable_x() { X_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; }
#else
#define enable_x() ;
#define disable_x() ;
@ -124,11 +124,11 @@ void manage_inactivity(bool ignore_stepper_queue=false);
#if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1
#ifdef Y_DUAL_STEPPER_DRIVERS
#define enable_y() { WRITE(Y_ENABLE_PIN, Y_ENABLE_ON); WRITE(Y2_ENABLE_PIN, Y_ENABLE_ON); }
#define disable_y() { WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON); WRITE(Y2_ENABLE_PIN, !Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }
#define enable_y() { Y_ENABLE_WRITE( Y_ENABLE_ON); Y2_ENABLE_WRITE(Y_ENABLE_ON); }
#define disable_y() { Y_ENABLE_WRITE(!Y_ENABLE_ON); Y2_ENABLE_WRITE(!Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }
#else
#define enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON)
#define disable_y() { WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }
#define enable_y() Y_ENABLE_WRITE( Y_ENABLE_ON)
#define disable_y() { Y_ENABLE_WRITE(!Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }
#endif
#else
#define enable_y() ;
@ -137,11 +137,11 @@ void manage_inactivity(bool ignore_stepper_queue=false);
#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
#ifdef Z_DUAL_STEPPER_DRIVERS
#define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
#define enable_z() { Z_ENABLE_WRITE( Z_ENABLE_ON); Z2_ENABLE_WRITE(Z_ENABLE_ON); }
#define disable_z() { Z_ENABLE_WRITE(!Z_ENABLE_ON); Z2_ENABLE_WRITE(!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
#else
#define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
#define enable_z() Z_ENABLE_WRITE( Z_ENABLE_ON)
#define disable_z() { Z_ENABLE_WRITE(!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
#endif
#else
#define enable_z() ;
@ -149,32 +149,32 @@ void manage_inactivity(bool ignore_stepper_queue=false);
#endif
#if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1)
#define enable_e0() WRITE(E0_ENABLE_PIN, E_ENABLE_ON)
#define disable_e0() WRITE(E0_ENABLE_PIN,!E_ENABLE_ON)
#define enable_e0() E0_ENABLE_WRITE(E_ENABLE_ON)
#define disable_e0() E0_ENABLE_WRITE(!E_ENABLE_ON)
#else
#define enable_e0() /* nothing */
#define disable_e0() /* nothing */
#endif
#if (EXTRUDERS > 1) && defined(E1_ENABLE_PIN) && (E1_ENABLE_PIN > -1)
#define enable_e1() WRITE(E1_ENABLE_PIN, E_ENABLE_ON)
#define disable_e1() WRITE(E1_ENABLE_PIN,!E_ENABLE_ON)
#define enable_e1() E1_ENABLE_WRITE(E_ENABLE_ON)
#define disable_e1() E1_ENABLE_WRITE(!E_ENABLE_ON)
#else
#define enable_e1() /* nothing */
#define disable_e1() /* nothing */
#endif
#if (EXTRUDERS > 2) && defined(E2_ENABLE_PIN) && (E2_ENABLE_PIN > -1)
#define enable_e2() WRITE(E2_ENABLE_PIN, E_ENABLE_ON)
#define disable_e2() WRITE(E2_ENABLE_PIN,!E_ENABLE_ON)
#define enable_e2() E2_ENABLE_WRITE(E_ENABLE_ON)
#define disable_e2() E2_ENABLE_WRITE(!E_ENABLE_ON)
#else
#define enable_e2() /* nothing */
#define disable_e2() /* nothing */
#endif
#if (EXTRUDERS > 3) && defined(E3_ENABLE_PIN) && (E3_ENABLE_PIN > -1)
#define enable_e3() WRITE(E3_ENABLE_PIN, E_ENABLE_ON)
#define disable_e3() WRITE(E3_ENABLE_PIN,!E_ENABLE_ON)
#define enable_e3() E3_ENABLE_WRITE(E_ENABLE_ON)
#define disable_e3() E3_ENABLE_WRITE(!E_ENABLE_ON)
#else
#define enable_e3() /* nothing */
#define disable_e3() /* nothing */

View file

@ -54,3 +54,13 @@
#if defined(DIGIPOT_I2C)
#include <Wire.h>
#endif
#ifdef HAVE_TMCDRIVER
#include <SPI.h>
#include <TMC26XStepper.h>
#endif
#ifdef HAVE_L6470DRIVER
#include <SPI.h>
#include <L6470.h>
#endif

View file

@ -39,6 +39,8 @@
#endif
#endif // ENABLE_AUTO_BED_LEVELING
#define SERVO_LEVELING defined(ENABLE_AUTO_BED_LEVELING) && PROBE_SERVO_DEACTIVATION_DELAY > 0
#include "ultralcd.h"
#include "planner.h"
#include "stepper.h"
@ -199,6 +201,10 @@
#endif
float homing_feedrate[] = HOMING_FEEDRATE;
#ifdef ENABLE_AUTO_BED_LEVELING
int xy_travel_speed = XY_TRAVEL_SPEED;
#endif
int homing_bump_divisor[] = HOMING_BUMP_DIVISOR;
bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
int feedmultiply = 100; //100->1 200->2
int saved_feedmultiply;
@ -589,9 +595,9 @@ void servo_init()
}
#endif
#if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
delay(PROBE_SERVO_DEACTIVATION_DELAY);
servos[servo_endstops[Z_AXIS]].detach();
#if SERVO_LEVELING
delay(PROBE_SERVO_DEACTIVATION_DELAY);
servos[servo_endstops[Z_AXIS]].detach();
#endif
}
@ -730,103 +736,113 @@ void get_command()
serial_char = MYSERIAL.read();
if(serial_char == '\n' ||
serial_char == '\r' ||
(serial_char == ':' && comment_mode == false) ||
serial_count >= (MAX_CMD_SIZE - 1) )
{
if(!serial_count) { //if empty line
comment_mode = false; //for new command
// end of line == end of comment
comment_mode = false;
if(!serial_count) {
// short cut for empty lines
return;
}
cmdbuffer[bufindw][serial_count] = 0; //terminate string
if(!comment_mode){
comment_mode = false; //for new command
fromsd[bufindw] = false;
if(strchr(cmdbuffer[bufindw], 'N') != NULL)
fromsd[bufindw] = false;
if(strchr(cmdbuffer[bufindw], 'N') != NULL)
{
strchr_pointer = strchr(cmdbuffer[bufindw], 'N');
gcode_N = (strtol(strchr_pointer + 1, NULL, 10));
if(gcode_N != gcode_LastN+1 && (strstr_P(cmdbuffer[bufindw], PSTR("M110")) == NULL) ) {
SERIAL_ERROR_START;
SERIAL_ERRORPGM(MSG_ERR_LINE_NO);
SERIAL_ERRORLN(gcode_LastN);
//Serial.println(gcode_N);
FlushSerialRequestResend();
serial_count = 0;
return;
}
if(strchr(cmdbuffer[bufindw], '*') != NULL)
{
strchr_pointer = strchr(cmdbuffer[bufindw], 'N');
gcode_N = (strtol(strchr_pointer + 1, NULL, 10));
if(gcode_N != gcode_LastN+1 && (strstr_P(cmdbuffer[bufindw], PSTR("M110")) == NULL) ) {
SERIAL_ERROR_START;
SERIAL_ERRORPGM(MSG_ERR_LINE_NO);
SERIAL_ERRORLN(gcode_LastN);
//Serial.println(gcode_N);
FlushSerialRequestResend();
serial_count = 0;
return;
}
byte checksum = 0;
byte count = 0;
while(cmdbuffer[bufindw][count] != '*') checksum = checksum^cmdbuffer[bufindw][count++];
strchr_pointer = strchr(cmdbuffer[bufindw], '*');
if(strchr(cmdbuffer[bufindw], '*') != NULL)
{
byte checksum = 0;
byte count = 0;
while(cmdbuffer[bufindw][count] != '*') checksum = checksum^cmdbuffer[bufindw][count++];
strchr_pointer = strchr(cmdbuffer[bufindw], '*');
if( (int)(strtod(strchr_pointer + 1, NULL)) != checksum) {
SERIAL_ERROR_START;
SERIAL_ERRORPGM(MSG_ERR_CHECKSUM_MISMATCH);
SERIAL_ERRORLN(gcode_LastN);
FlushSerialRequestResend();
serial_count = 0;
return;
}
//if no errors, continue parsing
}
else
{
if(strtol(strchr_pointer + 1, NULL, 10) != checksum) {
SERIAL_ERROR_START;
SERIAL_ERRORPGM(MSG_ERR_NO_CHECKSUM);
SERIAL_ERRORPGM(MSG_ERR_CHECKSUM_MISMATCH);
SERIAL_ERRORLN(gcode_LastN);
FlushSerialRequestResend();
serial_count = 0;
return;
}
gcode_LastN = gcode_N;
//if no errors, continue parsing
}
else // if we don't receive 'N' but still see '*'
else
{
if((strchr(cmdbuffer[bufindw], '*') != NULL))
{
SERIAL_ERROR_START;
SERIAL_ERRORPGM(MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM);
SERIAL_ERRORLN(gcode_LastN);
serial_count = 0;
return;
}
}
if((strchr(cmdbuffer[bufindw], 'G') != NULL)){
strchr_pointer = strchr(cmdbuffer[bufindw], 'G');
switch((int)((strtod(strchr_pointer + 1, NULL)))){
case 0:
case 1:
case 2:
case 3:
if (Stopped == true) {
SERIAL_ERRORLNPGM(MSG_ERR_STOPPED);
LCD_MESSAGEPGM(MSG_STOPPED);
}
break;
default:
break;
}
SERIAL_ERROR_START;
SERIAL_ERRORPGM(MSG_ERR_NO_CHECKSUM);
SERIAL_ERRORLN(gcode_LastN);
FlushSerialRequestResend();
serial_count = 0;
return;
}
//If command was e-stop process now
if(strcmp(cmdbuffer[bufindw], "M112") == 0)
kill();
bufindw = (bufindw + 1)%BUFSIZE;
buflen += 1;
gcode_LastN = gcode_N;
//if no errors, continue parsing
}
else // if we don't receive 'N' but still see '*'
{
if((strchr(cmdbuffer[bufindw], '*') != NULL))
{
SERIAL_ERROR_START;
SERIAL_ERRORPGM(MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM);
SERIAL_ERRORLN(gcode_LastN);
serial_count = 0;
return;
}
}
if((strchr(cmdbuffer[bufindw], 'G') != NULL)){
strchr_pointer = strchr(cmdbuffer[bufindw], 'G');
switch(strtol(strchr_pointer + 1, NULL, 10)){
case 0:
case 1:
case 2:
case 3:
if (Stopped == true) {
SERIAL_ERRORLNPGM(MSG_ERR_STOPPED);
LCD_MESSAGEPGM(MSG_STOPPED);
}
break;
default:
break;
}
}
//If command was e-stop process now
if(strcmp(cmdbuffer[bufindw], "M112") == 0)
kill();
bufindw = (bufindw + 1)%BUFSIZE;
buflen += 1;
serial_count = 0; //clear buffer
}
else
{
if(serial_char == ';') comment_mode = true;
if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char;
else if(serial_char == '\\') { //Handle escapes
if(MYSERIAL.available() > 0 && buflen < BUFSIZE) {
// if we have one more character, copy it over
serial_char = MYSERIAL.read();
cmdbuffer[bufindw][serial_count++] = serial_char;
}
//otherwise do nothing
}
else { // its not a newline, carriage return or escape char
if(serial_char == ';') comment_mode = true;
if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char;
}
}
#ifdef SDSUPPORT
@ -1119,7 +1135,18 @@ static void run_z_probe() {
st_synchronize();
// move back down slowly to find bed
feedrate = homing_feedrate[Z_AXIS]/4;
if (homing_bump_divisor[Z_AXIS] >= 1)
{
feedrate = homing_feedrate[Z_AXIS]/homing_bump_divisor[Z_AXIS];
}
else
{
feedrate = homing_feedrate[Z_AXIS]/10;
SERIAL_ECHOLN("Warning: The Homing Bump Feedrate Divisor cannot be less then 1");
}
zPosition -= home_retract_mm(Z_AXIS) * 2;
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate/60, active_extruder);
st_synchronize();
@ -1138,7 +1165,7 @@ static void do_blocking_move_to(float x, float y, float z) {
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate/60, active_extruder);
st_synchronize();
feedrate = XY_TRAVEL_SPEED;
feedrate = xy_travel_speed;
current_position[X_AXIS] = x;
current_position[Y_AXIS] = y;
@ -1172,41 +1199,41 @@ static void clean_up_after_endstop_move() {
}
static void engage_z_probe() {
// Engage Z Servo endstop if enabled
#ifdef SERVO_ENDSTOPS
// Engage Z Servo endstop if enabled
#ifdef SERVO_ENDSTOPS
if (servo_endstops[Z_AXIS] > -1) {
#if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
#if SERVO_LEVELING
servos[servo_endstops[Z_AXIS]].attach(0);
#endif
servos[servo_endstops[Z_AXIS]].write(servo_endstop_angles[Z_AXIS * 2]);
#if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
#endif
servos[servo_endstops[Z_AXIS]].write(servo_endstop_angles[Z_AXIS * 2]);
#if SERVO_LEVELING
delay(PROBE_SERVO_DEACTIVATION_DELAY);
servos[servo_endstops[Z_AXIS]].detach();
#endif
#endif
}
#endif
#endif
}
static void retract_z_probe() {
// Retract Z Servo endstop if enabled
#ifdef SERVO_ENDSTOPS
// Retract Z Servo endstop if enabled
#ifdef SERVO_ENDSTOPS
if (servo_endstops[Z_AXIS] > -1) {
#if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
#if SERVO_LEVELING
servos[servo_endstops[Z_AXIS]].attach(0);
#endif
servos[servo_endstops[Z_AXIS]].write(servo_endstop_angles[Z_AXIS * 2 + 1]);
#if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
#endif
servos[servo_endstops[Z_AXIS]].write(servo_endstop_angles[Z_AXIS * 2 + 1]);
#if SERVO_LEVELING
delay(PROBE_SERVO_DEACTIVATION_DELAY);
servos[servo_endstops[Z_AXIS]].detach();
#endif
#endif
}
#endif
#endif
}
enum ProbeAction { ProbeStay, ProbeEngage, ProbeRetract, ProbeEngageRetract };
/// Probe bed height at position (x,y), returns the measured z value
static float probe_pt(float x, float y, float z_before, ProbeAction retract_action=ProbeEngageRetract) {
static float probe_pt(float x, float y, float z_before, ProbeAction retract_action=ProbeEngageRetract, int verbose_level=1) {
// move to right place
do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z_before);
do_blocking_move_to(x - X_PROBE_OFFSET_FROM_EXTRUDER, y - Y_PROBE_OFFSET_FROM_EXTRUDER, current_position[Z_AXIS]);
@ -1222,18 +1249,20 @@ static float probe_pt(float x, float y, float z_before, ProbeAction retract_acti
if (retract_action & ProbeRetract) retract_z_probe();
#endif
SERIAL_PROTOCOLPGM(MSG_BED);
SERIAL_PROTOCOLPGM(" x: ");
SERIAL_PROTOCOL(x);
SERIAL_PROTOCOLPGM(" y: ");
SERIAL_PROTOCOL(y);
SERIAL_PROTOCOLPGM(" z: ");
SERIAL_PROTOCOL(measured_z);
SERIAL_PROTOCOLPGM("\n");
if (verbose_level > 2) {
SERIAL_PROTOCOLPGM(MSG_BED);
SERIAL_PROTOCOLPGM(" X: ");
SERIAL_PROTOCOL(x + 0.0001);
SERIAL_PROTOCOLPGM(" Y: ");
SERIAL_PROTOCOL(y + 0.0001);
SERIAL_PROTOCOLPGM(" Z: ");
SERIAL_PROTOCOL(measured_z + 0.0001);
SERIAL_EOL;
}
return measured_z;
}
#endif // #ifdef ENABLE_AUTO_BED_LEVELING
#endif // ENABLE_AUTO_BED_LEVELING
static void homeaxis(int axis) {
#define HOMEAXIS_DO(LETTER) \
@ -1256,7 +1285,7 @@ static void homeaxis(int axis) {
#ifndef Z_PROBE_SLED
// Engage Servo endstop if enabled
#ifdef SERVO_ENDSTOPS
#if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
#if SERVO_LEVELING
if (axis==Z_AXIS) {
engage_z_probe();
}
@ -1279,11 +1308,17 @@ static void homeaxis(int axis) {
st_synchronize();
destination[axis] = 2*home_retract_mm(axis) * axis_home_dir;
#ifdef DELTA
feedrate = homing_feedrate[axis]/10;
#else
feedrate = homing_feedrate[axis]/2 ;
#endif
if (homing_bump_divisor[axis] >= 1)
{
feedrate = homing_feedrate[axis]/homing_bump_divisor[axis];
}
else
{
feedrate = homing_feedrate[axis]/10;
SERIAL_ECHOLN("Warning: The Homing Bump Feedrate Divisor cannot be less then 1");
}
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
st_synchronize();
#ifdef DELTA
@ -1307,7 +1342,7 @@ static void homeaxis(int axis) {
servos[servo_endstops[axis]].write(servo_endstop_angles[axis * 2 + 1]);
}
#endif
#if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
#if SERVO_LEVELING
#ifndef Z_PROBE_SLED
if (axis==Z_AXIS) retract_z_probe();
#endif
@ -1734,6 +1769,44 @@ inline void gcode_G28() {
#ifdef ENABLE_AUTO_BED_LEVELING
// Define the possible boundaries for probing based on set limits
#define MIN_PROBE_X (max(X_MIN_POS, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
#define MAX_PROBE_X (min(X_MAX_POS, X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
#define MIN_PROBE_Y (max(Y_MIN_POS, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
#define MAX_PROBE_Y (min(Y_MAX_POS, Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
#ifdef AUTO_BED_LEVELING_GRID
// Make sure probing points are reachable
#if LEFT_PROBE_BED_POSITION < MIN_PROBE_X
#error "The given LEFT_PROBE_BED_POSITION can't be reached by the probe."
#elif RIGHT_PROBE_BED_POSITION > MAX_PROBE_X
#error "The given RIGHT_PROBE_BED_POSITION can't be reached by the probe."
#elif FRONT_PROBE_BED_POSITION < MIN_PROBE_Y
#error "The given FRONT_PROBE_BED_POSITION can't be reached by the probe."
#elif BACK_PROBE_BED_POSITION > MAX_PROBE_Y
#error "The given BACK_PROBE_BED_POSITION can't be reached by the probe."
#endif
#else // !AUTO_BED_LEVELING_GRID
#if ABL_PROBE_PT_1_X < MIN_PROBE_X || ABL_PROBE_PT_1_X > MAX_PROBE_X
#error "The given ABL_PROBE_PT_1_X can't be reached by the probe."
#elif ABL_PROBE_PT_2_X < MIN_PROBE_X || ABL_PROBE_PT_2_X > MAX_PROBE_X
#error "The given ABL_PROBE_PT_2_X can't be reached by the probe."
#elif ABL_PROBE_PT_3_X < MIN_PROBE_X || ABL_PROBE_PT_3_X > MAX_PROBE_X
#error "The given ABL_PROBE_PT_3_X can't be reached by the probe."
#elif ABL_PROBE_PT_1_Y < MIN_PROBE_Y || ABL_PROBE_PT_1_Y > MAX_PROBE_Y
#error "The given ABL_PROBE_PT_1_Y can't be reached by the probe."
#elif ABL_PROBE_PT_2_Y < MIN_PROBE_Y || ABL_PROBE_PT_2_Y > MAX_PROBE_Y
#error "The given ABL_PROBE_PT_2_Y can't be reached by the probe."
#elif ABL_PROBE_PT_3_Y < MIN_PROBE_Y || ABL_PROBE_PT_3_Y > MAX_PROBE_Y
#error "The given ABL_PROBE_PT_3_Y can't be reached by the probe."
#endif
#endif // !AUTO_BED_LEVELING_GRID
/**
* G29: Detailed Z-Probe, probes the bed at 3 or more points.
* Will fail if the printer has not been homed with G28.
@ -1745,6 +1818,8 @@ inline void gcode_G28() {
* P Set the size of the grid that will be probed (P x P points).
* Example: "G29 P4"
*
* S Set the XY travel speed between probe points (in mm/min)
*
* V Set the verbose level (0-4). Example: "G29 V3"
*
* T Generate a Bed Topology Report. Example: "G29 P5 T" for a detailed report.
@ -1772,8 +1847,6 @@ inline void gcode_G28() {
inline void gcode_G29() {
float x_tmp, y_tmp, z_tmp, real_z;
// Prevent user from running a G29 without first homing in X and Y
if (!axis_known_position[X_AXIS] || !axis_known_position[Y_AXIS]) {
LCD_MESSAGEPGM(MSG_POSITION_UNKNOWN);
@ -1782,76 +1855,64 @@ inline void gcode_G28() {
return;
}
int verbose_level = 1;
float x_tmp, y_tmp, z_tmp, real_z;
if (code_seen('V') || code_seen('v')) {
verbose_level = code_value_long();
if (verbose_level < 0 || verbose_level > 4) {
SERIAL_PROTOCOLPGM("?(V)erbose Level is implausible (0-4).\n");
return;
}
}
bool enhanced_g29 = code_seen('E') || code_seen('e');
#ifdef AUTO_BED_LEVELING_GRID
// Example Syntax: G29 N4 V2 E T
int verbose_level = 1;
bool topo_flag = verbose_level > 2 || code_seen('T') || code_seen('t');
bool topo_flag = code_seen('T') || code_seen('t');
if (code_seen('V') || code_seen('v')) {
verbose_level = code_value();
if (verbose_level < 0 || verbose_level > 4) {
SERIAL_PROTOCOLPGM("?(V)erbose Level is implausible (0-4).\n");
return;
}
if (verbose_level > 0) {
SERIAL_PROTOCOLPGM("G29 Enhanced Auto Bed Leveling Code V1.25:\n");
SERIAL_PROTOCOLPGM("Full support at: http://3dprintboard.com/forum.php\n");
if (verbose_level > 2) topo_flag = true;
}
}
if (verbose_level > 0)
SERIAL_PROTOCOLPGM("G29 Auto Bed Leveling\n");
int auto_bed_leveling_grid_points = code_seen('P') ? code_value_long() : AUTO_BED_LEVELING_GRID_POINTS;
if (auto_bed_leveling_grid_points < 2 || auto_bed_leveling_grid_points > AUTO_BED_LEVELING_GRID_POINTS) {
if (auto_bed_leveling_grid_points < 2) {
SERIAL_PROTOCOLPGM("?Number of probed (P)oints is implausible (2 minimum).\n");
return;
}
// Define the possible boundaries for probing based on the set limits.
// Code above (in G28) might have these limits wrong, or I am wrong here.
#define MIN_PROBE_EDGE 10 // Edges of the probe square can be no less
const int min_probe_x = max(X_MIN_POS, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER),
max_probe_x = min(X_MAX_POS, X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER),
min_probe_y = max(Y_MIN_POS, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER),
max_probe_y = min(Y_MAX_POS, Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER);
xy_travel_speed = code_seen('S') ? code_value_long() : XY_TRAVEL_SPEED;
int left_probe_bed_position = code_seen('L') ? code_value_long() : LEFT_PROBE_BED_POSITION,
right_probe_bed_position = code_seen('R') ? code_value_long() : RIGHT_PROBE_BED_POSITION,
front_probe_bed_position = code_seen('F') ? code_value_long() : FRONT_PROBE_BED_POSITION,
back_probe_bed_position = code_seen('B') ? code_value_long() : BACK_PROBE_BED_POSITION;
bool left_out_l = left_probe_bed_position < min_probe_x,
left_out_r = left_probe_bed_position > right_probe_bed_position - MIN_PROBE_EDGE,
left_out = left_out_l || left_out_r,
right_out_r = right_probe_bed_position > max_probe_x,
right_out_l =right_probe_bed_position < left_probe_bed_position + MIN_PROBE_EDGE,
right_out = right_out_l || right_out_r,
front_out_f = front_probe_bed_position < min_probe_y,
front_out_b = front_probe_bed_position > back_probe_bed_position - MIN_PROBE_EDGE,
front_out = front_out_f || front_out_b,
back_out_b = back_probe_bed_position > max_probe_y,
back_out_f = back_probe_bed_position < front_probe_bed_position + MIN_PROBE_EDGE,
back_out = back_out_f || back_out_b;
bool left_out_l = left_probe_bed_position < MIN_PROBE_X,
left_out = left_out_l || left_probe_bed_position > right_probe_bed_position - MIN_PROBE_EDGE,
right_out_r = right_probe_bed_position > MAX_PROBE_X,
right_out = right_out_r || right_probe_bed_position < left_probe_bed_position + MIN_PROBE_EDGE,
front_out_f = front_probe_bed_position < MIN_PROBE_Y,
front_out = front_out_f || front_probe_bed_position > back_probe_bed_position - MIN_PROBE_EDGE,
back_out_b = back_probe_bed_position > MAX_PROBE_Y,
back_out = back_out_b || back_probe_bed_position < front_probe_bed_position + MIN_PROBE_EDGE;
if (left_out || right_out || front_out || back_out) {
if (left_out) {
SERIAL_PROTOCOLPGM("?Probe (L)eft position out of range.\n");
left_probe_bed_position = left_out_l ? min_probe_x : right_probe_bed_position - MIN_PROBE_EDGE;
left_probe_bed_position = left_out_l ? MIN_PROBE_X : right_probe_bed_position - MIN_PROBE_EDGE;
}
if (right_out) {
SERIAL_PROTOCOLPGM("?Probe (R)ight position out of range.\n");
right_probe_bed_position = right_out_r ? max_probe_x : left_probe_bed_position + MIN_PROBE_EDGE;
right_probe_bed_position = right_out_r ? MAX_PROBE_X : left_probe_bed_position + MIN_PROBE_EDGE;
}
if (front_out) {
SERIAL_PROTOCOLPGM("?Probe (F)ront position out of range.\n");
front_probe_bed_position = front_out_f ? min_probe_y : back_probe_bed_position - MIN_PROBE_EDGE;
front_probe_bed_position = front_out_f ? MIN_PROBE_Y : back_probe_bed_position - MIN_PROBE_EDGE;
}
if (back_out) {
SERIAL_PROTOCOLPGM("?Probe (B)ack position out of range.\n");
back_probe_bed_position = back_out_b ? max_probe_y : front_probe_bed_position + MIN_PROBE_EDGE;
back_probe_bed_position = back_out_b ? MAX_PROBE_Y : front_probe_bed_position + MIN_PROBE_EDGE;
}
return;
}
@ -1929,7 +1990,7 @@ inline void gcode_G28() {
else
act = ProbeEngageRetract;
measured_z = probe_pt(xProbe, yProbe, z_before, act);
measured_z = probe_pt(xProbe, yProbe, z_before, act, verbose_level);
mean += measured_z;
@ -1954,15 +2015,15 @@ inline void gcode_G28() {
if (verbose_level) {
SERIAL_PROTOCOLPGM("Eqn coefficients: a: ");
SERIAL_PROTOCOL(plane_equation_coefficients[0]);
SERIAL_PROTOCOL(plane_equation_coefficients[0] + 0.0001);
SERIAL_PROTOCOLPGM(" b: ");
SERIAL_PROTOCOL(plane_equation_coefficients[1]);
SERIAL_PROTOCOL(plane_equation_coefficients[1] + 0.0001);
SERIAL_PROTOCOLPGM(" d: ");
SERIAL_PROTOCOLLN(plane_equation_coefficients[2]);
SERIAL_PROTOCOLLN(plane_equation_coefficients[2] + 0.0001);
if (verbose_level > 2) {
SERIAL_PROTOCOLPGM("Mean of sampled points: ");
SERIAL_PROTOCOL_F(mean, 6);
SERIAL_PROTOCOLPGM(" \n");
SERIAL_EOL;
}
}
@ -1994,14 +2055,14 @@ inline void gcode_G28() {
;
float diff = eqnBVector[ind] - mean;
if (diff >= 0.0)
SERIAL_PROTOCOLPGM(" +"); // Watch column alignment in Pronterface
SERIAL_PROTOCOLPGM(" +"); // Include + for column alignment
else
SERIAL_PROTOCOLPGM(" -");
SERIAL_PROTOCOLPGM(" ");
SERIAL_PROTOCOL_F(diff, 5);
} // xx
SERIAL_PROTOCOLPGM("\n");
SERIAL_EOL;
} // yy
SERIAL_PROTOCOLPGM("\n");
SERIAL_EOL;
} //topo_flag
@ -2016,14 +2077,14 @@ inline void gcode_G28() {
if (enhanced_g29) {
// Basic Enhanced G29
z_at_pt_1 = probe_pt(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, Z_RAISE_BEFORE_PROBING, ProbeEngage);
z_at_pt_2 = probe_pt(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS, ProbeStay);
z_at_pt_3 = probe_pt(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS, ProbeRetract);
z_at_pt_1 = probe_pt(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, Z_RAISE_BEFORE_PROBING, ProbeEngage, verbose_level);
z_at_pt_2 = probe_pt(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS, ProbeStay, verbose_level);
z_at_pt_3 = probe_pt(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS, ProbeRetract, verbose_level);
}
else {
z_at_pt_1 = probe_pt(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, Z_RAISE_BEFORE_PROBING);
z_at_pt_2 = probe_pt(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS);
z_at_pt_3 = probe_pt(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS);
z_at_pt_1 = probe_pt(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, Z_RAISE_BEFORE_PROBING, verbose_level);
z_at_pt_2 = probe_pt(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS, verbose_level);
z_at_pt_3 = probe_pt(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS, verbose_level);
}
clean_up_after_endstop_move();
set_bed_level_equation_3pts(z_at_pt_1, z_at_pt_2, z_at_pt_3);
@ -2035,7 +2096,7 @@ inline void gcode_G28() {
if (verbose_level > 0)
plan_bed_level_matrix.debug(" \n\nBed Level Correction Matrix:");
// The following code correct the Z height difference from z-probe position and hotend tip position.
// Correct the Z height difference from z-probe position and hotend tip position.
// The Z height on homing is measured by Z-Probe, but the probe is quite far from the hotend.
// When the bed is uneven, this height must be corrected.
real_z = float(st_get_position(Z_AXIS)) / axis_steps_per_unit[Z_AXIS]; //get the real Z (since the auto bed leveling is already correcting the plane)
@ -2050,6 +2111,11 @@ inline void gcode_G28() {
#ifdef Z_PROBE_SLED
dock_sled(true, -SLED_DOCKING_OFFSET); // dock the probe, correcting for over-travel
#endif
#ifdef Z_PROBE_END_SCRIPT
enquecommands_P(PSTR(Z_PROBE_END_SCRIPT));
st_synchronize();
#endif
}
#ifndef Z_PROBE_SLED
@ -2065,12 +2131,12 @@ inline void gcode_G28() {
run_z_probe();
SERIAL_PROTOCOLPGM(MSG_BED);
SERIAL_PROTOCOLPGM(" X: ");
SERIAL_PROTOCOL(current_position[X_AXIS]);
SERIAL_PROTOCOL(current_position[X_AXIS] + 0.0001);
SERIAL_PROTOCOLPGM(" Y: ");
SERIAL_PROTOCOL(current_position[Y_AXIS]);
SERIAL_PROTOCOL(current_position[Y_AXIS] + 0.0001);
SERIAL_PROTOCOLPGM(" Z: ");
SERIAL_PROTOCOL(current_position[Z_AXIS]);
SERIAL_PROTOCOLPGM("\n");
SERIAL_PROTOCOL(current_position[Z_AXIS] + 0.0001);
SERIAL_EOL;
clean_up_after_endstop_move();
retract_z_probe(); // Retract Z Servo endstop if available
@ -2418,10 +2484,8 @@ inline void gcode_M42() {
}
}
if (verbose_level > 0) {
SERIAL_PROTOCOLPGM("M48 Z-Probe Repeatability test. Version 2.00\n");
SERIAL_PROTOCOLPGM("Full support at: http://3dprintboard.com/forum.php\n");
}
if (verbose_level > 0)
SERIAL_PROTOCOLPGM("M48 Z-Probe Repeatability test\n");
if (code_seen('n')) {
n_samples = code_value();
@ -2435,7 +2499,7 @@ inline void gcode_M42() {
Y_current = Y_probe_location = st_get_position_mm(Y_AXIS);
Z_current = st_get_position_mm(Z_AXIS);
Z_start_location = st_get_position_mm(Z_AXIS) + Z_RAISE_BEFORE_PROBING;
ext_position = st_get_position_mm(E_AXIS);
ext_position = st_get_position_mm(E_AXIS);
if (code_seen('E') || code_seen('e'))
engage_probe_for_each_reading++;
@ -2599,8 +2663,7 @@ inline void gcode_M42() {
SERIAL_PROTOCOL_F(sigma,6);
}
if (verbose_level > 0)
SERIAL_PROTOCOLPGM("\n");
if (verbose_level > 0) SERIAL_EOL;
plan_buffer_line(X_probe_location, Y_probe_location, Z_start_location,
current_position[E_AXIS], homing_feedrate[Z_AXIS]/60, active_extruder);
@ -2622,12 +2685,12 @@ inline void gcode_M42() {
if (verbose_level > 0) {
SERIAL_PROTOCOLPGM("Mean: ");
SERIAL_PROTOCOL_F(mean, 6);
SERIAL_PROTOCOLPGM("\n");
SERIAL_EOL;
}
SERIAL_PROTOCOLPGM("Standard Deviation: ");
SERIAL_PROTOCOL_F(sigma, 6);
SERIAL_PROTOCOLPGM("\n\n");
SERIAL_EOL; SERIAL_EOL;
}
#endif // ENABLE_AUTO_BED_LEVELING && Z_PROBE_REPEATABILITY_TEST
@ -3200,16 +3263,34 @@ inline void gcode_M203() {
}
/**
* M204: Set Default Acceleration and/or Default Filament Acceleration in mm/sec^2 (M204 S3000 T7000)
* M204: Set Accelerations in mm/sec^2 (M204 P1200 R3000 T3000)
*
* S = normal moves
* T = filament only moves
* P = Printing moves
* R = Retract only (no X, Y, Z) moves
* T = Travel (non printing) moves
*
* Also sets minimum segment time in ms (B20000) to prevent buffer under-runs and M20 minimum feedrate
*/
inline void gcode_M204() {
if (code_seen('S')) acceleration = code_value();
if (code_seen('T')) retract_acceleration = code_value();
if (code_seen('P'))
{
acceleration = code_value();
SERIAL_ECHOPAIR("Setting Printing Acceleration: ", acceleration );
SERIAL_EOL;
}
if (code_seen('R'))
{
retract_acceleration = code_value();
SERIAL_ECHOPAIR("Setting Retract Acceleration: ", retract_acceleration );
SERIAL_EOL;
}
if (code_seen('T'))
{
travel_acceleration = code_value();
SERIAL_ECHOPAIR("Setting Travel Acceleration: ", travel_acceleration );
SERIAL_EOL;
}
}
/**
@ -3434,11 +3515,11 @@ inline void gcode_M226() {
if (code_seen('S')) {
servo_position = code_value();
if ((servo_index >= 0) && (servo_index < NUM_SERVOS)) {
#if defined(ENABLE_AUTO_BED_LEVELING) && PROBE_SERVO_DEACTIVATION_DELAY > 0
#if SERVO_LEVELING
servos[servo_index].attach(0);
#endif
servos[servo_index].write(servo_position);
#if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
#if SERVO_LEVELING
delay(PROBE_SERVO_DEACTIVATION_DELAY);
servos[servo_index].detach();
#endif
@ -4156,7 +4237,7 @@ inline void gcode_M350() {
*/
inline void gcode_M351() {
#if defined(X_MS1_PIN) && X_MS1_PIN > -1
if (code_seen('S')) switch((int)code_value()) {
if (code_seen('S')) switch(code_value_long()) {
case 1:
for(int i=0;i<NUM_AXIS;i++) if (code_seen(axis_codes[i])) microstep_ms(i, code_value(), -1);
if (code_seen('B')) microstep_ms(4, code_value(), -1);
@ -4355,7 +4436,7 @@ void process_commands() {
}
else if (code_seen('M')) {
switch( (int)code_value() ) {
switch( code_value_long() ) {
#ifdef ULTIPANEL
case 0: // M0 - Unconditional stop - Wait for user button press on LCD
case 1: // M1 - Conditional stop - Wait for user button press on LCD
@ -5038,18 +5119,18 @@ void controllerFan()
if ((millis() - lastMotorCheck) >= 2500) //Not a time critical function, so we only check every 2500ms
{
lastMotorCheck = millis();
if((!READ(X_ENABLE_PIN) ^ !(X_ENABLE_ON)) || (!READ(Y_ENABLE_PIN) ^ !(Y_ENABLE_ON)) || (!READ(Z_ENABLE_PIN) ^ !(Z_ENABLE_ON)) || (soft_pwm_bed > 0)
if((X_ENABLE_READ) == (X_ENABLE_ON)) || (Y_ENABLE_READ) == (Y_ENABLE_ON)) || (Z_ENABLE_READ) == (Z_ENABLE_ON)) || (soft_pwm_bed > 0)
#if EXTRUDERS > 2
|| (!READ(E2_ENABLE_PIN) ^ !(E_ENABLE_ON))
|| (E2_ENABLE_READ) == (E_ENABLE_ON))
#endif
#if EXTRUDER > 1
#if defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1
|| (!READ(X2_ENABLE_PIN) ^ !(X_ENABLE_ON))
|| (X2_ENABLE_READ) == (X_ENABLE_ON))
#endif
|| (!READ(E1_ENABLE_PIN) ^ !(E_ENABLE_ON))
|| (E1_ENABLE_READ) == (E_ENABLE_ON))
#endif
|| (!READ(E0_ENABLE_PIN) ^ !(E_ENABLE_ON))) //If any of the drivers are enabled...
|| (E0_ENABLE_READ) == (E_ENABLE_ON))) //If any of the drivers are enabled...
{
lastMotor = millis(); //... set time to NOW so the fan will turn on
}
@ -5274,7 +5355,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument s
if( (millis() - previous_millis_cmd) > EXTRUDER_RUNOUT_SECONDS*1000 )
if(degHotend(active_extruder)>EXTRUDER_RUNOUT_MINTEMP)
{
bool oldstatus=READ(E0_ENABLE_PIN);
bool oldstatus=E0_ENABLE_READ;
enable_e0();
float oldepos=current_position[E_AXIS];
float oldedes=destination[E_AXIS];
@ -5286,7 +5367,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument s
plan_set_e_position(oldepos);
previous_millis_cmd=millis();
st_synchronize();
WRITE(E0_ENABLE_PIN,oldstatus);
E0_ENABLE_WRITE(oldstatus);
}
#endif
#if defined(DUAL_X_CARRIAGE)

View file

@ -82,7 +82,7 @@ Here are some standard links for getting your machine calibrated:
// #define PS_DEFAULT_OFF
//===========================================================================
//============================= Thermal Settings ============================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
@ -118,6 +118,10 @@ Here are some standard links for getting your machine calibrated:
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
// #define DUMMY_THERMISTOR_998_VALUE 25
// #define DUMMY_THERMISTOR_999_VALUE 100
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
@ -297,9 +301,12 @@ your extruder heater takes 2 minutes to hit the target on heating.
//============================= Mechanical Settings =========================
//===========================================================================
// Uncomment the following line to enable CoreXY kinematics
// Uncomment this option to enable CoreXY kinematics
// #define COREXY
// Enable this option for Toshiba steppers
// #define CONFIG_STEPPERS_TOSHIBA
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
@ -332,11 +339,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define DISABLE_MAX_ENDSTOPS
//#define DISABLE_MIN_ENDSTOPS
// Disable max endstops for compatibility with endstop checking routine
#if defined(COREXY) && !defined(DISABLE_MAX_ENDSTOPS)
#define DISABLE_MAX_ENDSTOPS
#endif
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
@ -389,40 +391,40 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#ifdef ENABLE_AUTO_BED_LEVELING
// There are 2 different ways to pick the X and Y locations to probe:
// - "grid" mode
// Probe every point in a rectangular grid
// You must specify the rectangle, and the density of sample points
// This mode is preferred because there are more measurements.
// It used to be called ACCURATE_BED_LEVELING but "grid" is more descriptive
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You must specify the X & Y coordinates of all 3 points
// There are 2 different ways to specify probing locations
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You specify the XY coordinates of all 3 points.
// Enable this to sample the bed in a grid (least squares solution)
// Note: this feature generates 10KB extra code size
#define AUTO_BED_LEVELING_GRID
// with AUTO_BED_LEVELING_GRID, the bed is sampled in a
// AUTO_BED_LEVELING_GRID_POINTSxAUTO_BED_LEVELING_GRID_POINTS grid
// and least squares solution is calculated
// Note: this feature occupies 10'206 byte
#ifdef AUTO_BED_LEVELING_GRID
// set the rectangle in which to probe
// The edges of the rectangle in which to probe
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define BACK_PROBE_BED_POSITION 180
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#define MIN_PROBE_EDGE 10 // The probe square sides can be no smaller than this
// set the number of grid points per dimension
// I wouldn't see a reason to go above 3 (=9 probing points on the bed)
// Set the number of grid points per dimension
// You probably don't need more than 3 (squared=9)
#define AUTO_BED_LEVELING_GRID_POINTS 2
#else // not AUTO_BED_LEVELING_GRID
// with no grid, just probe 3 arbitrary points. A simple cross-product
// is used to esimate the plane of the print bed
#else // !AUTO_BED_LEVELING_GRID
// Arbitrary points to probe. A simple cross-product
// is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
@ -433,11 +435,11 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#endif // AUTO_BED_LEVELING_GRID
// these are the offsets to the probe relative to the extruder tip (Hotend - Probe)
// Offsets to the probe relative to the extruder tip (Hotend - Probe)
// X and Y offsets must be integers
#define X_PROBE_OFFSET_FROM_EXTRUDER -25
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // -left +right
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // -front +behind
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // -below (always!)
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z before homing (G28) for Probe Clearance.
// Be sure you have this distance over your Z_MAX_POS in case
@ -474,29 +476,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#endif
#ifdef AUTO_BED_LEVELING_GRID // Check if Probe_Offset * Grid Points is greater than Probing Range
#if X_PROBE_OFFSET_FROM_EXTRUDER < 0
#if (-(X_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION))
#error "The X axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#else
#if ((X_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION))
#error "The X axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#endif
#if Y_PROBE_OFFSET_FROM_EXTRUDER < 0
#if (-(Y_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION))
#error "The Y axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#else
#if ((Y_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION))
#error "The Y axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#endif
#endif
#endif // ENABLE_AUTO_BED_LEVELING
@ -521,8 +500,11 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DEFAULT_MAX_FEEDRATE {250, 250, 3.3, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {3000,3000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
@ -536,9 +518,9 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DEFAULT_EJERK 5.0 // (mm/sec)
//===========================================================================
//============================= Additional Features =========================
//===========================================================================
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
// Custom M code points
#define CUSTOM_M_CODES
@ -569,7 +551,12 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
//LCD and SD support
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
// Character based displays can have different extended charsets.
#define DISPLAY_CHARSET_HD44780_JAPAN // "ääööüüß23°"
@ -583,7 +570,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
@ -750,7 +737,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define SDSUPPORT
#define ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the DOG graphic display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 20
@ -759,7 +746,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#else //no panel but just LCD
#ifdef ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 16

View file

@ -214,6 +214,7 @@
#define X_HOME_RETRACT_MM 5
#define Y_HOME_RETRACT_MM 5
#define Z_HOME_RETRACT_MM 2
#define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
#define AXIS_RELATIVE_MODES {false, false, false, false}

View file

@ -3,13 +3,12 @@
#include "boards.h"
//===========================================================================
//============================= Getting Started =============================
//===========================================================================
/*
Here are some standard links for getting your machine calibrated:
* http://reprap.org/wiki/Calibration
* http://reprap.org/wiki/Calibration
* http://youtu.be/wAL9d7FgInk
* http://calculator.josefprusa.cz
* http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
@ -39,7 +38,7 @@ Here are some standard links for getting your machine calibrated:
// User-specified version info of this build to display in [Pronterface, etc] terminal window during
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "v1.0.2"
#define STRING_VERSION "1.0.2"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(K8200, CONSULitAS)" // Who made the changes.
@ -82,7 +81,6 @@ Here are some standard links for getting your machine calibrated:
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
// #define PS_DEFAULT_OFF
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
@ -120,6 +118,10 @@ Here are some standard links for getting your machine calibrated:
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
// #define DUMMY_THERMISTOR_998_VALUE 25
// #define DUMMY_THERMISTOR_999_VALUE 100
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 0
@ -260,7 +262,6 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//===========================================================================
@ -305,9 +306,12 @@ your extruder heater takes 2 minutes to hit the target on heating.
//============================= Mechanical Settings =========================
//===========================================================================
// Uncomment the following line to enable CoreXY kinematics
// Uncomment this option to enable CoreXY kinematics
// #define COREXY
// Enable this option for Toshiba steppers
// #define CONFIG_STEPPERS_TOSHIBA
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
@ -340,11 +344,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DISABLE_MAX_ENDSTOPS
//#define DISABLE_MIN_ENDSTOPS
// Disable max endstops for compatibility with endstop checking routine
#if defined(COREXY) && !defined(DISABLE_MAX_ENDSTOPS)
#define DISABLE_MAX_ENDSTOPS
#endif
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
@ -397,40 +396,40 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#ifdef ENABLE_AUTO_BED_LEVELING
// There are 2 different ways to pick the X and Y locations to probe:
// - "grid" mode
// Probe every point in a rectangular grid
// You must specify the rectangle, and the density of sample points
// This mode is preferred because there are more measurements.
// It used to be called ACCURATE_BED_LEVELING but "grid" is more descriptive
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You must specify the X & Y coordinates of all 3 points
// There are 2 different ways to specify probing locations
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You specify the XY coordinates of all 3 points.
// Enable this to sample the bed in a grid (least squares solution)
// Note: this feature generates 10KB extra code size
#define AUTO_BED_LEVELING_GRID
// with AUTO_BED_LEVELING_GRID, the bed is sampled in a
// AUTO_BED_LEVELING_GRID_POINTSxAUTO_BED_LEVELING_GRID_POINTS grid
// and least squares solution is calculated
// Note: this feature occupies 10'206 byte
#ifdef AUTO_BED_LEVELING_GRID
// set the rectangle in which to probe
// The edges of the rectangle in which to probe
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define BACK_PROBE_BED_POSITION 180
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// set the number of grid points per dimension
// I wouldn't see a reason to go above 3 (=9 probing points on the bed)
#define MIN_PROBE_EDGE 10 // The probe square sides can be no smaller than this
// Set the number of grid points per dimension
// You probably don't need more than 3 (squared=9)
#define AUTO_BED_LEVELING_GRID_POINTS 2
#else // not AUTO_BED_LEVELING_GRID
// with no grid, just probe 3 arbitrary points. A simple cross-product
// is used to esimate the plane of the print bed
#else // !AUTO_BED_LEVELING_GRID
// Arbitrary points to probe. A simple cross-product
// is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
@ -441,11 +440,11 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#endif // AUTO_BED_LEVELING_GRID
// these are the offsets to the probe relative to the extruder tip (Hotend - Probe)
// Offsets to the probe relative to the extruder tip (Hotend - Probe)
// X and Y offsets must be integers
#define X_PROBE_OFFSET_FROM_EXTRUDER -25
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // -left +right
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // -front +behind
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // -below (always!)
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z before homing (G28) for Probe Clearance.
// Be sure you have this distance over your Z_MAX_POS in case
@ -482,29 +481,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#endif
#ifdef AUTO_BED_LEVELING_GRID // Check if Probe_Offset * Grid Points is greater than Probing Range
#if X_PROBE_OFFSET_FROM_EXTRUDER < 0
#if (-(X_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION))
#error "The X axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#else
#if ((X_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION))
#error "The X axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#endif
#if Y_PROBE_OFFSET_FROM_EXTRUDER < 0
#if (-(Y_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION))
#error "The Y axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#else
#if ((Y_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION))
#error "The Y axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#endif
#endif
#endif // ENABLE_AUTO_BED_LEVELING
@ -529,8 +505,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 500} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
@ -544,9 +522,9 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DEFAULT_EJERK 5.0 // (mm/sec)
//===========================================================================
//============================= Additional Features =========================
//===========================================================================
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
// Custom M code points
#define CUSTOM_M_CODES
@ -577,9 +555,12 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ABS_PREHEAT_HPB_TEMP 60
#define ABS_PREHEAT_FAN_SPEED 0 // Insert Value between 0 and 255
//LCD and SD support
//==============================LCD and SD support=============================
// VM8201 (LCD Option for K8200) uses "DISPLAY_CHARSET_HD44870_JAPAN" and "ULTIMAKERCONTROLLER"
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
// Character based displays can have different extended charsets.
#define DISPLAY_CHARSET_HD44780_JAPAN // "ääööüüß23°"
@ -760,7 +741,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define SDSUPPORT
#define ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the DOG graphic display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 20
@ -769,7 +750,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#else //no panel but just LCD
#ifdef ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 16

View file

@ -214,6 +214,7 @@
#define X_HOME_RETRACT_MM 5
#define Y_HOME_RETRACT_MM 5
#define Z_HOME_RETRACT_MM 3
#define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
#define AXIS_RELATIVE_MODES {false, false, false, false}

View file

@ -3,13 +3,12 @@
#include "boards.h"
//===========================================================================
//============================= Getting Started =============================
//===========================================================================
/*
Here are some standard links for getting your machine calibrated:
* http://reprap.org/wiki/Calibration
* http://reprap.org/wiki/Calibration
* http://youtu.be/wAL9d7FgInk
* http://calculator.josefprusa.cz
* http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
@ -18,7 +17,6 @@ Here are some standard links for getting your machine calibrated:
* http://www.thingiverse.com/thing:298812
*/
// This configuration file contains the basic settings.
// Advanced settings can be found in Configuration_adv.h
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
@ -52,7 +50,7 @@ Here are some standard links for getting your machine calibrated:
#define L2_2 sq(Linkage_2) // do not change
//===========================================================================
//========================= SCARA Settings end ==================================
//========================= SCARA Settings end ==============================
//===========================================================================
// User-specified version info of this build to display in [Pronterface, etc] terminal window during
@ -70,7 +68,6 @@ Here are some standard links for getting your machine calibrated:
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// This determines the communication speed of the printer
#define BAUDRATE 250000
@ -125,6 +122,7 @@ Here are some standard links for getting your machine calibrated:
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
//
@ -138,6 +136,10 @@ Here are some standard links for getting your machine calibrated:
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
// #define DUMMY_THERMISTOR_998_VALUE 25
// #define DUMMY_THERMISTOR_999_VALUE 100
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
@ -189,31 +191,24 @@ Here are some standard links for getting your machine calibrated:
// Comment the following line to disable PID and enable bang-bang.
#define PIDTEMP
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX 255 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#ifdef PIDTEMP
//#define PID_DEBUG // Sends debug data to the serial port.
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
//#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
//#define PID_PARAMS_PER_EXTRUDER // Uses separate PID parameters for each extruder (useful for mismatched extruders)
// Set/get with gcode: M301 E[extruder number, 0-2]
#define PID_FUNCTIONAL_RANGE 20 // If the temperature difference between the target temperature and the actual temperature
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX 255 //limit for the integral term
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define K1 0.95 //smoothing factor within the PID
#define PID_dT ((OVERSAMPLENR * 8.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine
#define PID_dT ((OVERSAMPLENR * 10.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
// #define DEFAULT_Kp 22.2
// #define DEFAULT_Ki 1.08
// #define DEFAULT_Kd 114
// Jhead MK5: From Autotune
// #define DEFAULT_Kp 20.92
// #define DEFAULT_Ki 1.51
// #define DEFAULT_Kd 72.34
//Merlin Hotend: From Autotune
#define DEFAULT_Kp 24.5
#define DEFAULT_Ki 1.72
#define DEFAULT_Kd 87.73
// #define DEFAULT_Kp 22.2
// #define DEFAULT_Ki 1.08
// #define DEFAULT_Kd 114
// MakerGear
// #define DEFAULT_Kp 7.0
@ -221,9 +216,20 @@ Here are some standard links for getting your machine calibrated:
// #define DEFAULT_Kd 12
// Mendel Parts V9 on 12V
// #define DEFAULT_Kp 63.0
// #define DEFAULT_Ki 2.25
// #define DEFAULT_Kd 440
// #define DEFAULT_Kp 63.0
// #define DEFAULT_Ki 2.25
// #define DEFAULT_Kd 440
// Jhead MK5: From Autotune
// #define DEFAULT_Kp 20.92
// #define DEFAULT_Ki 1.51
// #define DEFAULT_Kd 72.34
// Merlin Hotend: From Autotune
#define DEFAULT_Kp 24.5
#define DEFAULT_Ki 1.72
#define DEFAULT_Kd 87.73
#endif // PIDTEMP
//===========================================================================
@ -251,9 +257,9 @@ Here are some standard links for getting your machine calibrated:
#ifdef PIDTEMPBED
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
// #define DEFAULT_bedKp 10.00
// #define DEFAULT_bedKi .023
// #define DEFAULT_bedKd 305.4
// #define DEFAULT_bedKp 10.00
// #define DEFAULT_bedKi .023
// #define DEFAULT_bedKd 305.4
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from pidautotune
@ -271,7 +277,6 @@ Here are some standard links for getting your machine calibrated:
#endif // PIDTEMPBED
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
//#define PREVENT_DANGEROUS_EXTRUDE
@ -281,7 +286,6 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MINTEMP 150
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//===========================================================================
@ -323,12 +327,15 @@ your extruder heater takes 2 minutes to hit the target on heating.
//===========================================================================
//============================ Mechanical Settings ==========================
//============================= Mechanical Settings =========================
//===========================================================================
// Uncomment the following line to enable CoreXY kinematics
// Uncomment this option to enable CoreXY kinematics
// #define COREXY
// Enable this option for Toshiba steppers
// #define CONFIG_STEPPERS_TOSHIBA
// coarse Endstop Settings
//#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
@ -361,11 +368,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define DISABLE_MAX_ENDSTOPS
//#define DISABLE_MIN_ENDSTOPS
// Disable max endstops for compatibility with endstop checking routine
#if defined(COREXY) && !defined(DISABLE_MAX_ENDSTOPS)
#define DISABLE_MAX_ENDSTOPS
#endif
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
@ -388,7 +390,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define INVERT_E3_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
// ENDSTOP SETTINGS:
// Sets direction of endstop s when homing; 1=MAX, -1=MIN
// Sets direction of endstops when homing; 1=MAX, -1=MIN
#define X_HOME_DIR 1
#define Y_HOME_DIR 1
#define Z_HOME_DIR -1
@ -414,43 +416,44 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//===========================================================================
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
#define Z_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
#ifdef ENABLE_AUTO_BED_LEVELING
// There are 2 different ways to pick the X and Y locations to probe:
// - "grid" mode
// Probe every point in a rectangular grid
// You must specify the rectangle, and the density of sample points
// This mode is preferred because there are more measurements.
// It used to be called ACCURATE_BED_LEVELING but "grid" is more descriptive
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You must specify the X & Y coordinates of all 3 points
// There are 2 different ways to specify probing locations
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You specify the XY coordinates of all 3 points.
// Enable this to sample the bed in a grid (least squares solution)
// Note: this feature generates 10KB extra code size
#define AUTO_BED_LEVELING_GRID
// with AUTO_BED_LEVELING_GRID, the bed is sampled in a
// AUTO_BED_LEVELING_GRID_POINTSxAUTO_BED_LEVELING_GRID_POINTS grid
// and least squares solution is calculated
// Note: this feature occupies 10'206 byte
#ifdef AUTO_BED_LEVELING_GRID
// set the rectangle in which to probe
// The edges of the rectangle in which to probe
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define BACK_PROBE_BED_POSITION 180
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// set the number of grid points per dimension
// I wouldn't see a reason to go above 3 (=9 probing points on the bed)
#define MIN_PROBE_EDGE 10 // The probe square sides can be no smaller than this
// Set the number of grid points per dimension
// You probably don't need more than 3 (squared=9)
#define AUTO_BED_LEVELING_GRID_POINTS 2
#else // not AUTO_BED_LEVELING_GRID
// with no grid, just probe 3 arbitrary points. A simple cross-product
// is used to esimate the plane of the print bed
#else // !AUTO_BED_LEVELING_GRID
// Arbitrary points to probe. A simple cross-product
// is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
@ -461,10 +464,11 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#endif // AUTO_BED_LEVELING_GRID
// these are the offsets to the probe relative to the extruder tip (Hotend - Probe)
#define X_PROBE_OFFSET_FROM_EXTRUDER -25
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35
// Offsets to the probe relative to the extruder tip (Hotend - Probe)
// X and Y offsets must be integers
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // -left +right
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // -front +behind
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // -below (always!)
//#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z before homing (G28) for Probe Clearance.
// Be sure you have this distance over your Z_MAX_POS in case
@ -474,6 +478,8 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define Z_RAISE_BEFORE_PROBING 15 //How much the extruder will be raised before traveling to the first probing point.
#define Z_RAISE_BETWEEN_PROBINGS 5 //How much the extruder will be raised when traveling from between next probing points
//#define Z_PROBE_SLED // turn on if you have a z-probe mounted on a sled like those designed by Charles Bell
//#define SLED_DOCKING_OFFSET 5 // the extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
//If defined, the Probe servo will be turned on only during movement and then turned off to avoid jerk
//The value is the delay to turn the servo off after powered on - depends on the servo speed; 300ms is good value, but you can try lower it.
@ -524,11 +530,14 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DEFAULT_MAX_FEEDRATE {300, 300, 30, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {300,300,20,1000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 400 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 2000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define DEFAULT_ACCELERATION 400 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 2000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 400 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
// The offset has to be X=0, Y=0 for extruder 0 hotend (default extruder).
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
// For the other hotends it is their distance from the extruder 0 hotend.
// #define EXTRUDER_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
// #define EXTRUDER_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
@ -539,9 +548,9 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DEFAULT_EJERK 3 // (mm/sec)
//===========================================================================
//============================= Additional Features =========================
//===========================================================================
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
// Custom M code points
//#define CUSTOM_M_CODES
@ -572,7 +581,12 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
//LCD and SD support
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
// Character based displays can have different extended charsets.
#define DISPLAY_CHARSET_HD44780_JAPAN // "ääööüüß23°"
@ -738,11 +752,13 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// Shift register panels
// ---------------------
// 2 wire Non-latching LCD SR from:
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
//#define SR_LCD
#ifdef SR_LCD
#define SR_LCD_2W_NL // Non latching 2 wire shift register
//#define NEWPANEL
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
//#define SAV_3DLCD
#ifdef SAV_3DLCD
#define SR_LCD_2W_NL // Non latching 2 wire shiftregister
#define NEWPANEL
#define ULTIPANEL
#endif
@ -751,7 +767,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define SDSUPPORT
#define ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the DOG graphic display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 20
@ -760,7 +776,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#else //no panel but just LCD
#ifdef ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 16
@ -844,13 +860,13 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// Uncomment below to enable
//#define FILAMENT_SENSOR
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0 //Enter the diameter (in mm) of the filament generally used (3.0 mm or 1.75 mm) - this is then used in the slicer software. Used for sensor reading validation
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
#define MAX_MEASUREMENT_DELAY 20 //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM and lower number saves RAM)
#define MAX_MEASUREMENT_DELAY 20 //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM and lower number saves RAM)
//defines used in the code
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially

View file

@ -214,6 +214,7 @@
#define X_HOME_RETRACT_MM 3
#define Y_HOME_RETRACT_MM 3
#define Z_HOME_RETRACT_MM 3
#define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
#ifdef SCARA
#define QUICK_HOME //SCARA needs Quickhome

View file

@ -3,13 +3,12 @@
#include "boards.h"
//===========================================================================
//============================= Getting Started =============================
//===========================================================================
/*
Here are some standard links for getting your machine calibrated:
* http://reprap.org/wiki/Calibration
* http://reprap.org/wiki/Calibration
* http://youtu.be/wAL9d7FgInk
* http://calculator.josefprusa.cz
* http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
@ -18,7 +17,6 @@ Here are some standard links for getting your machine calibrated:
* http://www.thingiverse.com/thing:298812
*/
// This configuration file contains the basic settings.
// Advanced settings can be found in Configuration_adv.h
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
@ -83,7 +81,6 @@ Here are some standard links for getting your machine calibrated:
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
// #define PS_DEFAULT_OFF
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
@ -121,6 +118,10 @@ Here are some standard links for getting your machine calibrated:
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
// #define DUMMY_THERMISTOR_998_VALUE 25
// #define DUMMY_THERMISTOR_999_VALUE 100
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
@ -164,7 +165,6 @@ Here are some standard links for getting your machine calibrated:
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
//===========================================================================
//============================= PID Settings ================================
//===========================================================================
@ -184,7 +184,7 @@ Here are some standard links for getting your machine calibrated:
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define K1 0.95 //smoothing factor within the PID
#define PID_dT ((OVERSAMPLENR * 8.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine
#define PID_dT ((OVERSAMPLENR * 10.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
@ -256,7 +256,6 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//===========================================================================
@ -301,9 +300,12 @@ your extruder heater takes 2 minutes to hit the target on heating.
//============================= Mechanical Settings =========================
//===========================================================================
// Uncomment the following line to enable CoreXY kinematics
// Uncomment this option to enable CoreXY kinematics
// #define COREXY
// Enable this option for Toshiba steppers
// #define CONFIG_STEPPERS_TOSHIBA
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
@ -336,11 +338,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define DISABLE_MAX_ENDSTOPS
//#define DISABLE_MIN_ENDSTOPS
// Disable max endstops for compatibility with endstop checking routine
#if defined(COREXY) && !defined(DISABLE_MAX_ENDSTOPS)
#define DISABLE_MAX_ENDSTOPS
#endif
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
@ -393,40 +390,40 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#ifdef ENABLE_AUTO_BED_LEVELING
// There are 2 different ways to pick the X and Y locations to probe:
// - "grid" mode
// Probe every point in a rectangular grid
// You must specify the rectangle, and the density of sample points
// This mode is preferred because there are more measurements.
// It used to be called ACCURATE_BED_LEVELING but "grid" is more descriptive
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You must specify the X & Y coordinates of all 3 points
// There are 2 different ways to specify probing locations
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You specify the XY coordinates of all 3 points.
// Enable this to sample the bed in a grid (least squares solution)
// Note: this feature generates 10KB extra code size
#define AUTO_BED_LEVELING_GRID
// with AUTO_BED_LEVELING_GRID, the bed is sampled in a
// AUTO_BED_LEVELING_GRID_POINTSxAUTO_BED_LEVELING_GRID_POINTS grid
// and least squares solution is calculated
// Note: this feature occupies 10'206 byte
#ifdef AUTO_BED_LEVELING_GRID
// set the rectangle in which to probe
// The edges of the rectangle in which to probe
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define BACK_PROBE_BED_POSITION 180
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// set the number of grid points per dimension
// I wouldn't see a reason to go above 3 (=9 probing points on the bed)
#define MIN_PROBE_EDGE 10 // The probe square sides can be no smaller than this
// Set the number of grid points per dimension
// You probably don't need more than 3 (squared=9)
#define AUTO_BED_LEVELING_GRID_POINTS 2
#else // not AUTO_BED_LEVELING_GRID
// with no grid, just probe 3 arbitrary points. A simple cross-product
// is used to esimate the plane of the print bed
#else // !AUTO_BED_LEVELING_GRID
// Arbitrary points to probe. A simple cross-product
// is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
@ -437,11 +434,11 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#endif // AUTO_BED_LEVELING_GRID
// these are the offsets to the probe relative to the extruder tip (Hotend - Probe)
// Offsets to the probe relative to the extruder tip (Hotend - Probe)
// X and Y offsets must be integers
#define X_PROBE_OFFSET_FROM_EXTRUDER -25
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // -left +right
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // -front +behind
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // -below (always!)
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z before homing (G28) for Probe Clearance.
// Be sure you have this distance over your Z_MAX_POS in case
@ -478,29 +475,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#endif
#ifdef AUTO_BED_LEVELING_GRID // Check if Probe_Offset * Grid Points is greater than Probing Range
#if X_PROBE_OFFSET_FROM_EXTRUDER < 0
#if (-(X_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION))
#error "The X axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#else
#if ((X_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION))
#error "The X axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#endif
#if Y_PROBE_OFFSET_FROM_EXTRUDER < 0
#if (-(Y_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION))
#error "The Y axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#else
#if ((Y_PROBE_OFFSET_FROM_EXTRUDER * (AUTO_BED_LEVELING_GRID_POINTS-1)) >= (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION))
#error "The Y axis probing range is not enough to fit all the points defined in AUTO_BED_LEVELING_GRID_POINTS"
#endif
#endif
#endif
#endif // ENABLE_AUTO_BED_LEVELING
@ -525,8 +499,9 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DEFAULT_MAX_FEEDRATE {350, 350, 7.2, 80} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {1000,1000,10,1000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
@ -540,9 +515,9 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DEFAULT_EJERK 5.0 // (mm/sec)
//===========================================================================
//============================ Additional Features ==========================
//===========================================================================
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
// Custom M code points
#define CUSTOM_M_CODES
@ -573,7 +548,12 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
//LCD and SD support
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
// Character based displays can have different extended charsets.
#define DISPLAY_CHARSET_HD44780_JAPAN // "ääööüüß23°"
@ -587,7 +567,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
@ -754,7 +734,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define SDSUPPORT
#define ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the DOG graphic display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 20
@ -763,7 +743,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#else //no panel but just LCD
#ifdef ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 16

View file

@ -214,6 +214,7 @@
#define X_HOME_RETRACT_MM 5
#define Y_HOME_RETRACT_MM 5
#define Z_HOME_RETRACT_MM 2
#define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
#define AXIS_RELATIVE_MODES {false, false, false, false}

View file

@ -1,15 +1,14 @@
#ifndef CONFIGURATION_H
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#include "boards.h"
//===========================================================================
//============================= Getting Started =============================
//===========================================================================
/*
Here are some standard links for getting your machine calibrated:
* http://reprap.org/wiki/Calibration
* http://reprap.org/wiki/Calibration
* http://youtu.be/wAL9d7FgInk
* http://calculator.josefprusa.cz
* http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
@ -22,7 +21,6 @@ Here are some standard links for getting your machine calibrated:
// Advanced settings can be found in Configuration_adv.h
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
//===========================================================================
//============================= DELTA Printer ===============================
//===========================================================================
@ -30,6 +28,13 @@ Here are some standard links for getting your machine calibrated:
// example_configurations/delta directory.
//
//===========================================================================
//============================= SCARA Printer ===============================
//===========================================================================
// For a Delta printer replace the configuration files with the files in the
// example_configurations/SCARA directory.
//
// User-specified version info of this build to display in [Pronterface, etc] terminal window during
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
@ -143,6 +148,10 @@ Here are some standard links for getting your machine calibrated:
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
// #define DUMMY_THERMISTOR_998_VALUE 25
// #define DUMMY_THERMISTOR_999_VALUE 100
#define TEMP_SENSOR_0 -1
#define TEMP_SENSOR_1 -1
@ -186,7 +195,6 @@ Here are some standard links for getting your machine calibrated:
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
//===========================================================================
//============================= PID Settings ================================
//===========================================================================
@ -195,13 +203,16 @@ Here are some standard links for getting your machine calibrated:
// Comment the following line to disable PID and enable bang-bang.
#define PIDTEMP
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX 255 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#ifdef PIDTEMP
//#define PID_DEBUG // Sends debug data to the serial port.
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
//#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
//#define PID_PARAMS_PER_EXTRUDER // Uses separate PID parameters for each extruder (useful for mismatched extruders)
// Set/get with gcode: M301 E[extruder number, 0-2]
#define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX 255 //limit for the integral term
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define K1 0.95 //smoothing factor within the PID
#define PID_dT ((OVERSAMPLENR * 10.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine
@ -222,7 +233,6 @@ Here are some standard links for getting your machine calibrated:
// #define DEFAULT_Kd 440
#endif // PIDTEMP
//===========================================================================
//============================= PID > Bed Temperature Control ===============
//===========================================================================
@ -271,7 +281,6 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//===========================================================================
@ -316,6 +325,12 @@ your extruder heater takes 2 minutes to hit the target on heating.
//============================= Mechanical Settings =========================
//===========================================================================
// Uncomment this option to enable CoreXY kinematics
// #define COREXY
// Enable this option for Toshiba steppers
// #define CONFIG_STEPPERS_TOSHIBA
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
@ -348,10 +363,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define DISABLE_MAX_ENDSTOPS
// Deltas never have min endstops
#define DISABLE_MIN_ENDSTOPS
// Disable max endstops for compatibility with endstop checking routine
#if defined(COREXY) && !defined(DISABLE_MAX_ENDSTOPS)
#define DISABLE_MAX_ENDSTOPS
#endif
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
#define X_ENABLE_ON 0
@ -397,6 +408,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
//===========================================================================
//============================= Bed Auto Leveling ===========================
//===========================================================================
@ -407,12 +419,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// The position of the homing switches
//#define MANUAL_HOME_POSITIONS // If defined, MANUAL_*_HOME_POS below will be used
#define MANUAL_HOME_POSITIONS // If defined, MANUAL_*_HOME_POS below will be used
//#define BED_CENTER_AT_0_0 // If defined, the center of the bed is at (X=0, Y=0)
//Manual homing switch locations:
#define MANUAL_HOME_POSITIONS // MANUAL_*_HOME_POS below will be used
// For deltabots this means top and center of the Cartesian print volume.
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS 0
@ -430,8 +440,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DEFAULT_MAX_FEEDRATE {500, 500, 500, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,9000,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
@ -444,9 +456,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DEFAULT_ZJERK 20.0 // (mm/sec) Must be same as XY for delta
#define DEFAULT_EJERK 5.0 // (mm/sec)
//===========================================================================
//============================= Additional Features =========================
//===========================================================================
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
// Custom M code points
#define CUSTOM_M_CODES
@ -477,7 +490,12 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
//LCD and SD support
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
// Character based displays can have different extended charsets.
#define DISPLAY_CHARSET_HD44780_JAPAN // "ääööüüß23°"
@ -650,11 +668,13 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// Shift register panels
// ---------------------
// 2 wire Non-latching LCD SR from:
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
//#define SR_LCD
#ifdef SR_LCD
#define SR_LCD_2W_NL // Non latching 2 wire shift register
//#define NEWPANEL
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
//#define SAV_3DLCD
#ifdef SAV_3DLCD
#define SR_LCD_2W_NL // Non latching 2 wire shiftregister
#define NEWPANEL
#define ULTIPANEL
#endif
@ -663,7 +683,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define SDSUPPORT
#define ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the DOG graphic display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 20
@ -672,7 +692,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#else //no panel but just LCD
#ifdef ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 16
@ -756,13 +776,13 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// Uncomment below to enable
//#define FILAMENT_SENSOR
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0 //Enter the diameter (in mm) of the filament generally used (3.0 mm or 1.75 mm) - this is then used in the slicer software. Used for sensor reading validation
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
#define MAX_MEASUREMENT_DELAY 20 //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM and lower number saves RAM)
#define MAX_MEASUREMENT_DELAY 20 //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM and lower number saves RAM)
//defines used in the code
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
@ -775,7 +795,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#include "Configuration_adv.h"
#include "thermistortables.h"

View file

@ -214,6 +214,7 @@
#define X_HOME_RETRACT_MM 5
#define Y_HOME_RETRACT_MM 5
#define Z_HOME_RETRACT_MM 5 // deltas need the same for all three axis
#define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.

View file

@ -3,13 +3,12 @@
#include "boards.h"
//===========================================================================
//============================= Getting Started =============================
//===========================================================================
/*
Here are some standard links for getting your machine calibrated:
* http://reprap.org/wiki/Calibration
* http://reprap.org/wiki/Calibration
* http://youtu.be/wAL9d7FgInk
* http://calculator.josefprusa.cz
* http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
@ -18,12 +17,10 @@ Here are some standard links for getting your machine calibrated:
* http://www.thingiverse.com/thing:298812
*/
// This configuration file contains the basic settings.
// Advanced settings can be found in Configuration_adv.h
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
//===========================================================================
//============================= DELTA Printer ===============================
//===========================================================================
@ -31,7 +28,6 @@ Here are some standard links for getting your machine calibrated:
// example_configurations/delta directory.
//
//===========================================================================
//============================= SCARA Printer ===============================
//===========================================================================
@ -85,7 +81,6 @@ Here are some standard links for getting your machine calibrated:
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
// #define PS_DEFAULT_OFF
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
@ -123,6 +118,10 @@ Here are some standard links for getting your machine calibrated:
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
// #define DUMMY_THERMISTOR_998_VALUE 25
// #define DUMMY_THERMISTOR_999_VALUE 100
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
@ -166,7 +165,6 @@ Here are some standard links for getting your machine calibrated:
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
//===========================================================================
//============================= PID Settings ================================
//===========================================================================
@ -175,13 +173,16 @@ Here are some standard links for getting your machine calibrated:
// Comment the following line to disable PID and enable bang-bang.
#define PIDTEMP
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX 255 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#ifdef PIDTEMP
//#define PID_DEBUG // Sends debug data to the serial port.
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
//#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
//#define PID_PARAMS_PER_EXTRUDER // Uses separate PID parameters for each extruder (useful for mismatched extruders)
// Set/get with gcode: M301 E[extruder number, 0-2]
#define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX 255 //limit for the integral term
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define K1 0.95 //smoothing factor within the PID
#define PID_dT ((OVERSAMPLENR * 10.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine
@ -202,7 +203,6 @@ Here are some standard links for getting your machine calibrated:
// #define DEFAULT_Kd 440
#endif // PIDTEMP
//===========================================================================
//============================= PID > Bed Temperature Control ===============
//===========================================================================
@ -254,7 +254,6 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//===========================================================================
@ -296,12 +295,15 @@ your extruder heater takes 2 minutes to hit the target on heating.
//===========================================================================
//============================ Mechanical Settings ==========================
//============================= Mechanical Settings =========================
//===========================================================================
// Uncomment the following line to enable CoreXY kinematics
// Uncomment this option to enable CoreXY kinematics
// #define COREXY
// Enable this option for Toshiba steppers
// #define CONFIG_STEPPERS_TOSHIBA
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
@ -334,11 +336,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define DISABLE_MAX_ENDSTOPS
//#define DISABLE_MIN_ENDSTOPS
// Disable max endstops for compatibility with endstop checking routine
#if defined(COREXY) && !defined(DISABLE_MAX_ENDSTOPS)
#define DISABLE_MAX_ENDSTOPS
#endif
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
@ -391,40 +388,40 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#ifdef ENABLE_AUTO_BED_LEVELING
// There are 2 different ways to pick the X and Y locations to probe:
// - "grid" mode
// Probe every point in a rectangular grid
// You must specify the rectangle, and the density of sample points
// This mode is preferred because there are more measurements.
// It used to be called ACCURATE_BED_LEVELING but "grid" is more descriptive
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You must specify the X & Y coordinates of all 3 points
// There are 2 different ways to specify probing locations
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You specify the XY coordinates of all 3 points.
// Enable this to sample the bed in a grid (least squares solution)
// Note: this feature generates 10KB extra code size
#define AUTO_BED_LEVELING_GRID
// with AUTO_BED_LEVELING_GRID, the bed is sampled in a
// AUTO_BED_LEVELING_GRID_POINTSxAUTO_BED_LEVELING_GRID_POINTS grid
// and least squares solution is calculated
// Note: this feature occupies 10'206 byte
#ifdef AUTO_BED_LEVELING_GRID
// set the rectangle in which to probe
// The edges of the rectangle in which to probe
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define BACK_PROBE_BED_POSITION 180
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// set the number of grid points per dimension
// I wouldn't see a reason to go above 3 (=9 probing points on the bed)
#define MIN_PROBE_EDGE 10 // The probe square sides can be no smaller than this
// Set the number of grid points per dimension
// You probably don't need more than 3 (squared=9)
#define AUTO_BED_LEVELING_GRID_POINTS 2
#else // not AUTO_BED_LEVELING_GRID
// with no grid, just probe 3 arbitrary points. A simple cross-product
// is used to esimate the plane of the print bed
#else // !AUTO_BED_LEVELING_GRID
// Arbitrary points to probe. A simple cross-product
// is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
@ -435,10 +432,11 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#endif // AUTO_BED_LEVELING_GRID
// these are the offsets to the probe relative to the extruder tip (Hotend - Probe)
#define X_PROBE_OFFSET_FROM_EXTRUDER -25
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35
// Offsets to the probe relative to the extruder tip (Hotend - Probe)
// X and Y offsets must be integers
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // -left +right
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // -front +behind
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // -below (always!)
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z before homing (G28) for Probe Clearance.
// Be sure you have this distance over your Z_MAX_POS in case
@ -499,8 +497,9 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DEFAULT_MAX_FEEDRATE {60, 60, 20, 45} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {2000,2000,30,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
@ -514,9 +513,9 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DEFAULT_EJERK 5.0 // (mm/sec)
//===========================================================================
//============================ Additional Features ==========================
//===========================================================================
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
// Custom M code points
#define CUSTOM_M_CODES
@ -547,7 +546,12 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
//LCD and SD support
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
// Character based displays can have different extended charsets.
#define DISPLAY_CHARSET_HD44780_JAPAN // "ääööüüß23°"
@ -713,11 +717,13 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// Shift register panels
// ---------------------
// 2 wire Non-latching LCD SR from:
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
//#define SR_LCD
#ifdef SR_LCD
#define SR_LCD_2W_NL // Non latching 2 wire shift register
//#define NEWPANEL
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
//#define SAV_3DLCD
#ifdef SAV_3DLCD
#define SR_LCD_2W_NL // Non latching 2 wire shiftregister
#define NEWPANEL
#define ULTIPANEL
#endif
@ -726,7 +732,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define SDSUPPORT
#define ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the DOG graphic display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 20
@ -735,7 +741,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#else //no panel but just LCD
#ifdef ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 16

View file

@ -214,6 +214,7 @@
#define X_HOME_RETRACT_MM 5
#define Y_HOME_RETRACT_MM 5
#define Z_HOME_RETRACT_MM 2
#define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
#define AXIS_RELATIVE_MODES {false, false, false, false}

View file

@ -8,7 +8,7 @@
//===========================================================================
/*
Here are some standard links for getting your machine calibrated:
* http://reprap.org/wiki/Calibration
* http://reprap.org/wiki/Calibration
* http://youtu.be/wAL9d7FgInk
* http://calculator.josefprusa.cz
* http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
@ -17,12 +17,10 @@ Here are some standard links for getting your machine calibrated:
* http://www.thingiverse.com/thing:298812
*/
// This configuration file contains the basic settings.
// Advanced settings can be found in Configuration_adv.h
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
//===========================================================================
//============================= DELTA Printer ===============================
//===========================================================================
@ -30,7 +28,6 @@ Here are some standard links for getting your machine calibrated:
// example_configurations/delta directory.
//
//===========================================================================
//============================= SCARA Printer ===============================
//===========================================================================
@ -84,7 +81,6 @@ Here are some standard links for getting your machine calibrated:
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
// #define PS_DEFAULT_OFF
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
@ -122,6 +118,10 @@ Here are some standard links for getting your machine calibrated:
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
// #define DUMMY_THERMISTOR_998_VALUE 25
// #define DUMMY_THERMISTOR_999_VALUE 100
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 0
@ -156,8 +156,6 @@ Here are some standard links for getting your machine calibrated:
#define HEATER_3_MAXTEMP 275
#define BED_MAXTEMP 150
#define CONFIG_STEPPERS_TOSHIBA 1
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
@ -167,7 +165,6 @@ Here are some standard links for getting your machine calibrated:
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
//===========================================================================
//============================= PID Settings ================================
//===========================================================================
@ -176,13 +173,16 @@ Here are some standard links for getting your machine calibrated:
// Comment the following line to disable PID and enable bang-bang.
#define PIDTEMP
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX 255 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#ifdef PIDTEMP
//#define PID_DEBUG // Sends debug data to the serial port.
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
//#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
//#define PID_PARAMS_PER_EXTRUDER // Uses separate PID parameters for each extruder (useful for mismatched extruders)
// Set/get with gcode: M301 E[extruder number, 0-2]
#define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX 255 //limit for the integral term
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define K1 0.95 //smoothing factor within the PID
#define PID_dT ((OVERSAMPLENR * 10.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine
@ -208,7 +208,6 @@ Here are some standard links for getting your machine calibrated:
// #define DEFAULT_Kd 440
#endif // PIDTEMP
//===========================================================================
//============================= PID > Bed Temperature Control ===============
//===========================================================================
@ -257,7 +256,6 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//===========================================================================
@ -299,12 +297,15 @@ your extruder heater takes 2 minutes to hit the target on heating.
//===========================================================================
//============================ Mechanical Settings ==========================
//============================= Mechanical Settings =========================
//===========================================================================
// Uncomment the following line to enable CoreXY kinematics
// Uncomment this option to enable CoreXY kinematics
// #define COREXY
// Enable this option for Toshiba steppers
#define CONFIG_STEPPERS_TOSHIBA
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
@ -337,11 +338,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define DISABLE_MAX_ENDSTOPS
//#define DISABLE_MIN_ENDSTOPS
// Disable max endstops for compatibility with endstop checking routine
#if defined(COREXY) && !defined(DISABLE_MAX_ENDSTOPS)
#define DISABLE_MAX_ENDSTOPS
#endif
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
#define X_ENABLE_ON 1
#define Y_ENABLE_ON 1
@ -394,40 +390,40 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#ifdef ENABLE_AUTO_BED_LEVELING
// There are 2 different ways to pick the X and Y locations to probe:
// - "grid" mode
// Probe every point in a rectangular grid
// You must specify the rectangle, and the density of sample points
// This mode is preferred because there are more measurements.
// It used to be called ACCURATE_BED_LEVELING but "grid" is more descriptive
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You must specify the X & Y coordinates of all 3 points
// There are 2 different ways to specify probing locations
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You specify the XY coordinates of all 3 points.
// Enable this to sample the bed in a grid (least squares solution)
// Note: this feature generates 10KB extra code size
#define AUTO_BED_LEVELING_GRID
// with AUTO_BED_LEVELING_GRID, the bed is sampled in a
// AUTO_BED_LEVELING_GRID_POINTSxAUTO_BED_LEVELING_GRID_POINTS grid
// and least squares solution is calculated
// Note: this feature occupies 10'206 byte
#ifdef AUTO_BED_LEVELING_GRID
// set the rectangle in which to probe
// The edges of the rectangle in which to probe
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define BACK_PROBE_BED_POSITION 180
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#define MIN_PROBE_EDGE 10 // The probe square sides can be no smaller than this
// set the number of grid points per dimension
// I wouldn't see a reason to go above 3 (=9 probing points on the bed)
// Set the number of grid points per dimension
// You probably don't need more than 3 (squared=9)
#define AUTO_BED_LEVELING_GRID_POINTS 2
#else // not AUTO_BED_LEVELING_GRID
// with no grid, just probe 3 arbitrary points. A simple cross-product
// is used to esimate the plane of the print bed
#else // !AUTO_BED_LEVELING_GRID
// Arbitrary points to probe. A simple cross-product
// is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
@ -438,10 +434,11 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#endif // AUTO_BED_LEVELING_GRID
// these are the offsets to the probe relative to the extruder tip (Hotend - Probe)
#define X_PROBE_OFFSET_FROM_EXTRUDER -25
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35
// Offsets to the probe relative to the extruder tip (Hotend - Probe)
// X and Y offsets must be integers
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // -left +right
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // -front +behind
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // -below (always!)
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z before homing (G28) for Probe Clearance.
// Be sure you have this distance over your Z_MAX_POS in case
@ -498,22 +495,18 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// default settings
//#define DEFAULT_AXIS_STEPS_PER_UNIT {78.7402,78.7402,200.0*8/3,760*1.1} // default steps per unit for Ultimaker
//#define //DEFAULT_AXIS_STEPS_PER_UNIT {79.87, 79.87, 2566, 563,78} // Al's TVRR
//#define DEFAULT_AXIS_STEPS_PER_UNIT {79.87, 79.87, 2566, 563,78} // Al's TVRR
//#define DEFAULT_AXIS_STEPS_PER_UNIT {81.26, 80.01, 2561, 599.14} // Michel TVRR old
//#define DEFAULT_AXIS_STEPS_PER_UNIT {71.1, 71.1, 2560, 739.65} // Michel TVRR
#define DEFAULT_AXIS_STEPS_PER_UNIT {71.1, 71.1, 2560, 600} // David TVRR
//#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec) default
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 45} // (mm/sec) David TVRR
#define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
/* MICHEL: This has an impact on the "ripples" in print walls */
#define DEFAULT_ACCELERATION 500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
//#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define DEFAULT_ACCELERATION 500 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 500 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
@ -527,9 +520,9 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DEFAULT_EJERK 5.0 // (mm/sec)
//===========================================================================
//============================ Additional Features ==========================
//===========================================================================
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
// Custom M code points
#define CUSTOM_M_CODES
@ -560,7 +553,12 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
//LCD and SD support
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
// Character based displays can have different extended charsets.
#define DISPLAY_CHARSET_HD44780_JAPAN // "ääööüüß23°"
@ -726,11 +724,13 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// Shift register panels
// ---------------------
// 2 wire Non-latching LCD SR from:
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
//#define SR_LCD
#ifdef SR_LCD
#define SR_LCD_2W_NL // Non latching 2 wire shift register
//#define NEWPANEL
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
//#define SAV_3DLCD
#ifdef SAV_3DLCD
#define SR_LCD_2W_NL // Non latching 2 wire shiftregister
#define NEWPANEL
#define ULTIPANEL
#endif
@ -739,7 +739,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define SDSUPPORT
#define ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the DOG graphic display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 20
@ -748,7 +748,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#else //no panel but just LCD
#ifdef ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
#define LCD_WIDTH 20
#define LCD_WIDTH 22
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 16
@ -832,13 +832,13 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// Uncomment below to enable
//#define FILAMENT_SENSOR
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0 //Enter the diameter (in mm) of the filament generally used (3.0 mm or 1.75 mm) - this is then used in the slicer software. Used for sensor reading validation
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
#define MAX_MEASUREMENT_DELAY 20 //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM and lower number saves RAM)
#define MAX_MEASUREMENT_DELAY 20 //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM and lower number saves RAM)
//defines used in the code
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially

View file

@ -214,6 +214,7 @@
#define X_HOME_RETRACT_MM 5
#define Y_HOME_RETRACT_MM 5
#define Z_HOME_RETRACT_MM 1
#define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
#define AXIS_RELATIVE_MODES {false, false, false, false}

View file

@ -169,8 +169,8 @@
#define MSG_PID_TIMEOUT MSG_PID_AUTOTUNE_FAILED " timeout"
#define MSG_BIAS " bias: "
#define MSG_D " d: "
#define MSG_MIN " min: "
#define MSG_MAX " max: "
#define MSG_T_MIN " min: "
#define MSG_T_MAX " max: "
#define MSG_KU " Ku: "
#define MSG_TU " Tu: "
#define MSG_CLASSIC_PID " Classic PID "
@ -226,8 +226,7 @@
#define STR_h3 "3"
#define STR_Deg "\271"
#define STR_THERMOMETER "\002"
#endif
#ifdef DISPLAY_CHARSET_HD44780_WESTERN // HD44780 ROM Code: A02 (Western)
#elif defined(DISPLAY_CHARSET_HD44780_WESTERN) // HD44780 ROM Code: A02 (Western)
#define STR_Ae "\216"
#define STR_ae "\204"
#define STR_Oe "\211"
@ -239,6 +238,8 @@
#define STR_h3 "\263"
#define STR_Deg "\337"
#define STR_THERMOMETER "\002"
#elif defined(ULTRA_LCD)
#error You must enable either DISPLAY_CHARSET_HD44780_JAPAN or DISPLAY_CHARSET_HD44780_WESTERN for your LCD controller.
#endif
#endif
/*

View file

@ -233,6 +233,9 @@
#ifndef MSG_A_RETRACT
#define MSG_A_RETRACT "A-retract"
#endif
#ifndef MSG_A_TRAVEL
#define MSG_A_TRAVEL "A-travel"
#endif
#ifndef MSG_XSTEPS
#define MSG_XSTEPS "Xsteps/mm"
#endif

View file

@ -67,8 +67,9 @@ float max_feedrate[NUM_AXIS]; // set the max speeds
float axis_steps_per_unit[NUM_AXIS];
unsigned long max_acceleration_units_per_sq_second[NUM_AXIS]; // Use M201 to override by software
float minimumfeedrate;
float acceleration; // Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX
float acceleration; // Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all printing moves. M204 SXXXX
float retract_acceleration; // mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX
float travel_acceleration; // Travel acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all NON printing moves. M204 MXXXX
float max_xy_jerk; //speed than can be stopped at once, if i understand correctly.
float max_z_jerk;
float max_e_jerk;
@ -907,19 +908,24 @@ Having the real displacement of the head, we can calculate the total movement le
{
block->acceleration_st = ceil(retract_acceleration * steps_per_mm); // convert to: acceleration steps/sec^2
}
else if(block->steps_e == 0)
{
block->acceleration_st = ceil(travel_acceleration * steps_per_mm); // convert to: acceleration steps/sec^2
}
else
{
block->acceleration_st = ceil(acceleration * steps_per_mm); // convert to: acceleration steps/sec^2
// Limit acceleration per axis
if(((float)block->acceleration_st * (float)block->steps_x / (float)block->step_event_count) > axis_steps_per_sqr_second[X_AXIS])
block->acceleration_st = axis_steps_per_sqr_second[X_AXIS];
if(((float)block->acceleration_st * (float)block->steps_y / (float)block->step_event_count) > axis_steps_per_sqr_second[Y_AXIS])
block->acceleration_st = axis_steps_per_sqr_second[Y_AXIS];
if(((float)block->acceleration_st * (float)block->steps_e / (float)block->step_event_count) > axis_steps_per_sqr_second[E_AXIS])
block->acceleration_st = axis_steps_per_sqr_second[E_AXIS];
if(((float)block->acceleration_st * (float)block->steps_z / (float)block->step_event_count ) > axis_steps_per_sqr_second[Z_AXIS])
block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS];
}
// Limit acceleration per axis
if(((float)block->acceleration_st * (float)block->steps_x / (float)block->step_event_count) > axis_steps_per_sqr_second[X_AXIS])
block->acceleration_st = axis_steps_per_sqr_second[X_AXIS];
if(((float)block->acceleration_st * (float)block->steps_y / (float)block->step_event_count) > axis_steps_per_sqr_second[Y_AXIS])
block->acceleration_st = axis_steps_per_sqr_second[Y_AXIS];
if(((float)block->acceleration_st * (float)block->steps_e / (float)block->step_event_count) > axis_steps_per_sqr_second[E_AXIS])
block->acceleration_st = axis_steps_per_sqr_second[E_AXIS];
if(((float)block->acceleration_st * (float)block->steps_z / (float)block->step_event_count ) > axis_steps_per_sqr_second[Z_AXIS])
block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS];
block->acceleration = block->acceleration_st / steps_per_mm;
block->acceleration_rate = (long)((float)block->acceleration_st * (16777216.0 / (F_CPU / 8.0)));

View file

@ -112,6 +112,7 @@ extern unsigned long max_acceleration_units_per_sq_second[NUM_AXIS]; // Use M201
extern float minimumfeedrate;
extern float acceleration; // Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX
extern float retract_acceleration; // mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX
extern float travel_acceleration; // Travel acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all NON printing moves. M204 MXXXX
extern float max_xy_jerk; //speed than can be stopped at once, if i understand correctly.
extern float max_z_jerk;
extern float max_e_jerk;

View file

@ -33,7 +33,6 @@
#include <SPI.h>
#endif
//===========================================================================
//=============================public variables ============================
//===========================================================================
@ -88,6 +87,7 @@ static bool check_endstops = true;
volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0};
volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1};
//===========================================================================
//=============================functions ============================
//===========================================================================
@ -349,51 +349,51 @@ ISR(TIMER1_COMPA_vect)
if((out_bits & (1<<X_AXIS))!=0){
#ifdef DUAL_X_CARRIAGE
if (extruder_duplication_enabled){
WRITE(X_DIR_PIN, INVERT_X_DIR);
WRITE(X2_DIR_PIN, INVERT_X_DIR);
X_DIR_WRITE(INVERT_X_DIR);
X2_DIR_WRITE(INVERT_X_DIR);
}
else{
if (current_block->active_extruder != 0)
WRITE(X2_DIR_PIN, INVERT_X_DIR);
X2_DIR_WRITE(INVERT_X_DIR);
else
WRITE(X_DIR_PIN, INVERT_X_DIR);
X_DIR_WRITE(INVERT_X_DIR);
}
#else
WRITE(X_DIR_PIN, INVERT_X_DIR);
X_DIR_WRITE(INVERT_X_DIR);
#endif
count_direction[X_AXIS]=-1;
}
else{
#ifdef DUAL_X_CARRIAGE
if (extruder_duplication_enabled){
WRITE(X_DIR_PIN, !INVERT_X_DIR);
WRITE(X2_DIR_PIN, !INVERT_X_DIR);
X_DIR_WRITE(!INVERT_X_DIR);
X2_DIR_WRITE( !INVERT_X_DIR);
}
else{
if (current_block->active_extruder != 0)
WRITE(X2_DIR_PIN, !INVERT_X_DIR);
X2_DIR_WRITE(!INVERT_X_DIR);
else
WRITE(X_DIR_PIN, !INVERT_X_DIR);
X_DIR_WRITE(!INVERT_X_DIR);
}
#else
WRITE(X_DIR_PIN, !INVERT_X_DIR);
X_DIR_WRITE(!INVERT_X_DIR);
#endif
count_direction[X_AXIS]=1;
}
if((out_bits & (1<<Y_AXIS))!=0){
WRITE(Y_DIR_PIN, INVERT_Y_DIR);
Y_DIR_WRITE(INVERT_Y_DIR);
#ifdef Y_DUAL_STEPPER_DRIVERS
WRITE(Y2_DIR_PIN, !(INVERT_Y_DIR == INVERT_Y2_VS_Y_DIR));
Y2_DIR_WRITE(!(INVERT_Y_DIR == INVERT_Y2_VS_Y_DIR));
#endif
count_direction[Y_AXIS]=-1;
}
else{
WRITE(Y_DIR_PIN, !INVERT_Y_DIR);
Y_DIR_WRITE(!INVERT_Y_DIR);
#ifdef Y_DUAL_STEPPER_DRIVERS
WRITE(Y2_DIR_PIN, (INVERT_Y_DIR == INVERT_Y2_VS_Y_DIR));
Y2_DIR_WRITE((INVERT_Y_DIR == INVERT_Y2_VS_Y_DIR));
#endif
count_direction[Y_AXIS]=1;
@ -480,10 +480,10 @@ ISR(TIMER1_COMPA_vect)
}
if ((out_bits & (1<<Z_AXIS)) != 0) { // -direction
WRITE(Z_DIR_PIN,INVERT_Z_DIR);
Z_DIR_WRITE(INVERT_Z_DIR);
#ifdef Z_DUAL_STEPPER_DRIVERS
WRITE(Z2_DIR_PIN,INVERT_Z_DIR);
Z2_DIR_WRITE(INVERT_Z_DIR);
#endif
count_direction[Z_AXIS]=-1;
@ -501,10 +501,10 @@ ISR(TIMER1_COMPA_vect)
}
}
else { // +direction
WRITE(Z_DIR_PIN,!INVERT_Z_DIR);
Z_DIR_WRITE(!INVERT_Z_DIR);
#ifdef Z_DUAL_STEPPER_DRIVERS
WRITE(Z2_DIR_PIN,!INVERT_Z_DIR);
Z2_DIR_WRITE(!INVERT_Z_DIR);
#endif
count_direction[Z_AXIS]=1;
@ -554,54 +554,48 @@ ISR(TIMER1_COMPA_vect)
#endif //ADVANCE
counter_x += current_block->steps_x;
#ifdef CONFIG_STEPPERS_TOSHIBA
/* The toshiba stepper controller require much longer pulses
* tjerfore we 'stage' decompose the pulses between high, and
* low instead of doing each in turn. The extra tests add enough
* lag to allow it work with without needing NOPs */
if (counter_x > 0) {
WRITE(X_STEP_PIN, HIGH);
}
/* The Toshiba stepper controller require much longer pulses.
* So we 'stage' decompose the pulses between high and low
* instead of doing each in turn. The extra tests add enough
* lag to allow it work with without needing NOPs
*/
if (counter_x > 0) X_STEP_WRITE(HIGH);
counter_y += current_block->steps_y;
if (counter_y > 0) {
WRITE(Y_STEP_PIN, HIGH);
}
if (counter_y > 0) Y_STEP_WRITE(HIGH);
counter_z += current_block->steps_z;
if (counter_z > 0) {
WRITE(Z_STEP_PIN, HIGH);
}
if (counter_z > 0) Z_STEP_WRITE(HIGH);
#ifndef ADVANCE
counter_e += current_block->steps_e;
if (counter_e > 0) {
WRITE_E_STEP(HIGH);
}
if (counter_e > 0) WRITE_E_STEP(HIGH);
#endif //!ADVANCE
if (counter_x > 0) {
counter_x -= current_block->step_event_count;
count_position[X_AXIS]+=count_direction[X_AXIS];
WRITE(X_STEP_PIN, LOW);
count_position[X_AXIS] += count_direction[X_AXIS];
X_STEP_WRITE(LOW);
}
if (counter_y > 0) {
counter_y -= current_block->step_event_count;
count_position[Y_AXIS]+=count_direction[Y_AXIS];
WRITE(Y_STEP_PIN, LOW);
count_position[Y_AXIS] += count_direction[Y_AXIS];
Y_STEP_WRITE( LOW);
}
if (counter_z > 0) {
counter_z -= current_block->step_event_count;
count_position[Z_AXIS]+=count_direction[Z_AXIS];
WRITE(Z_STEP_PIN, LOW);
count_position[Z_AXIS] += count_direction[Z_AXIS];
Z_STEP_WRITE(LOW);
}
#ifndef ADVANCE
if (counter_e > 0) {
counter_e -= current_block->step_event_count;
count_position[E_AXIS]+=count_direction[E_AXIS];
count_position[E_AXIS] += count_direction[E_AXIS];
WRITE_E_STEP(LOW);
}
#endif //!ADVANCE
@ -609,67 +603,66 @@ ISR(TIMER1_COMPA_vect)
if (counter_x > 0) {
#ifdef DUAL_X_CARRIAGE
if (extruder_duplication_enabled){
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
WRITE(X2_STEP_PIN, !INVERT_X_STEP_PIN);
X_STEP_WRITE(!INVERT_X_STEP_PIN);
X2_STEP_WRITE( !INVERT_X_STEP_PIN);
}
else {
if (current_block->active_extruder != 0)
WRITE(X2_STEP_PIN, !INVERT_X_STEP_PIN);
X2_STEP_WRITE( !INVERT_X_STEP_PIN);
else
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
X_STEP_WRITE(!INVERT_X_STEP_PIN);
}
#else
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
X_STEP_WRITE(!INVERT_X_STEP_PIN);
#endif
counter_x -= current_block->step_event_count;
count_position[X_AXIS]+=count_direction[X_AXIS];
count_position[X_AXIS] += count_direction[X_AXIS];
#ifdef DUAL_X_CARRIAGE
if (extruder_duplication_enabled){
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
WRITE(X2_STEP_PIN, INVERT_X_STEP_PIN);
X_STEP_WRITE(INVERT_X_STEP_PIN);
X2_STEP_WRITE(INVERT_X_STEP_PIN);
}
else {
if (current_block->active_extruder != 0)
WRITE(X2_STEP_PIN, INVERT_X_STEP_PIN);
X2_STEP_WRITE(INVERT_X_STEP_PIN);
else
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
X_STEP_WRITE(INVERT_X_STEP_PIN);
}
#else
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
X_STEP_WRITE(INVERT_X_STEP_PIN);
#endif
}
counter_y += current_block->steps_y;
if (counter_y > 0) {
WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
#ifdef Y_DUAL_STEPPER_DRIVERS
WRITE(Y2_STEP_PIN, !INVERT_Y_STEP_PIN);
Y2_STEP_WRITE( !INVERT_Y_STEP_PIN);
#endif
counter_y -= current_block->step_event_count;
count_position[Y_AXIS]+=count_direction[Y_AXIS];
WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
count_position[Y_AXIS] += count_direction[Y_AXIS];
Y_STEP_WRITE(INVERT_Y_STEP_PIN);
#ifdef Y_DUAL_STEPPER_DRIVERS
WRITE(Y2_STEP_PIN, INVERT_Y_STEP_PIN);
Y2_STEP_WRITE( INVERT_Y_STEP_PIN);
#endif
}
counter_z += current_block->steps_z;
if (counter_z > 0) {
WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
Z_STEP_WRITE( !INVERT_Z_STEP_PIN);
#ifdef Z_DUAL_STEPPER_DRIVERS
WRITE(Z2_STEP_PIN, !INVERT_Z_STEP_PIN);
Z2_STEP_WRITE(!INVERT_Z_STEP_PIN);
#endif
counter_z -= current_block->step_event_count;
count_position[Z_AXIS]+=count_direction[Z_AXIS];
WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN);
count_position[Z_AXIS] += count_direction[Z_AXIS];
Z_STEP_WRITE( INVERT_Z_STEP_PIN);
#ifdef Z_DUAL_STEPPER_DRIVERS
WRITE(Z2_STEP_PIN, INVERT_Z_STEP_PIN);
Z2_STEP_WRITE(INVERT_Z_STEP_PIN);
#endif
}
@ -678,7 +671,7 @@ ISR(TIMER1_COMPA_vect)
if (counter_e > 0) {
WRITE_E_STEP(!INVERT_E_STEP_PIN);
counter_e -= current_block->step_event_count;
count_position[E_AXIS]+=count_direction[E_AXIS];
count_position[E_AXIS] += count_direction[E_AXIS];
WRITE_E_STEP(INVERT_E_STEP_PIN);
}
#endif //!ADVANCE
@ -766,60 +759,60 @@ ISR(TIMER1_COMPA_vect)
// Set E direction (Depends on E direction + advance)
for(unsigned char i=0; i<4;i++) {
if (e_steps[0] != 0) {
WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN);
E0_STEP_WRITE( INVERT_E_STEP_PIN);
if (e_steps[0] < 0) {
WRITE(E0_DIR_PIN, INVERT_E0_DIR);
E0_DIR_WRITE(INVERT_E0_DIR);
e_steps[0]++;
WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
E0_STEP_WRITE(!INVERT_E_STEP_PIN);
}
else if (e_steps[0] > 0) {
WRITE(E0_DIR_PIN, !INVERT_E0_DIR);
E0_DIR_WRITE(!INVERT_E0_DIR);
e_steps[0]--;
WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
E0_STEP_WRITE(!INVERT_E_STEP_PIN);
}
}
#if EXTRUDERS > 1
if (e_steps[1] != 0) {
WRITE(E1_STEP_PIN, INVERT_E_STEP_PIN);
E1_STEP_WRITE(INVERT_E_STEP_PIN);
if (e_steps[1] < 0) {
WRITE(E1_DIR_PIN, INVERT_E1_DIR);
E1_DIR_WRITE(INVERT_E1_DIR);
e_steps[1]++;
WRITE(E1_STEP_PIN, !INVERT_E_STEP_PIN);
E1_STEP_WRITE(!INVERT_E_STEP_PIN);
}
else if (e_steps[1] > 0) {
WRITE(E1_DIR_PIN, !INVERT_E1_DIR);
E1_DIR_WRITE(!INVERT_E1_DIR);
e_steps[1]--;
WRITE(E1_STEP_PIN, !INVERT_E_STEP_PIN);
E1_STEP_WRITE(!INVERT_E_STEP_PIN);
}
}
#endif
#if EXTRUDERS > 2
if (e_steps[2] != 0) {
WRITE(E2_STEP_PIN, INVERT_E_STEP_PIN);
E2_STEP_WRITE(INVERT_E_STEP_PIN);
if (e_steps[2] < 0) {
WRITE(E2_DIR_PIN, INVERT_E2_DIR);
E2_DIR_WRITE(INVERT_E2_DIR);
e_steps[2]++;
WRITE(E2_STEP_PIN, !INVERT_E_STEP_PIN);
E2_STEP_WRITE(!INVERT_E_STEP_PIN);
}
else if (e_steps[2] > 0) {
WRITE(E2_DIR_PIN, !INVERT_E2_DIR);
E2_DIR_WRITE(!INVERT_E2_DIR);
e_steps[2]--;
WRITE(E2_STEP_PIN, !INVERT_E_STEP_PIN);
E2_STEP_WRITE(!INVERT_E_STEP_PIN);
}
}
#endif
#if EXTRUDERS > 3
if (e_steps[3] != 0) {
WRITE(E3_STEP_PIN, INVERT_E_STEP_PIN);
E3_STEP_WRITE(INVERT_E_STEP_PIN);
if (e_steps[3] < 0) {
WRITE(E3_DIR_PIN, INVERT_E3_DIR);
E3_DIR_WRITE(INVERT_E3_DIR);
e_steps[3]++;
WRITE(E3_STEP_PIN, !INVERT_E_STEP_PIN);
E3_STEP_WRITE(!INVERT_E_STEP_PIN);
}
else if (e_steps[3] > 0) {
WRITE(E3_DIR_PIN, !INVERT_E3_DIR);
E3_DIR_WRITE(!INVERT_E3_DIR);
e_steps[3]--;
WRITE(E3_STEP_PIN, !INVERT_E_STEP_PIN);
E3_STEP_WRITE(!INVERT_E_STEP_PIN);
}
}
#endif
@ -833,83 +826,93 @@ void st_init()
digipot_init(); //Initialize Digipot Motor Current
microstep_init(); //Initialize Microstepping Pins
// initialise TMC Steppers
#ifdef HAVE_TMCDRIVER
tmc_init();
#endif
// initialise L6470 Steppers
#ifdef HAVE_L6470DRIVER
L6470_init();
#endif
//Initialize Dir Pins
#if defined(X_DIR_PIN) && X_DIR_PIN > -1
SET_OUTPUT(X_DIR_PIN);
X_DIR_INIT;
#endif
#if defined(X2_DIR_PIN) && X2_DIR_PIN > -1
SET_OUTPUT(X2_DIR_PIN);
X2_DIR_INIT;
#endif
#if defined(Y_DIR_PIN) && Y_DIR_PIN > -1
SET_OUTPUT(Y_DIR_PIN);
Y_DIR_INIT;
#if defined(Y_DUAL_STEPPER_DRIVERS) && defined(Y2_DIR_PIN) && (Y2_DIR_PIN > -1)
SET_OUTPUT(Y2_DIR_PIN);
Y2_DIR_INIT;
#endif
#endif
#if defined(Z_DIR_PIN) && Z_DIR_PIN > -1
SET_OUTPUT(Z_DIR_PIN);
Z_DIR_INIT;
#if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_DIR_PIN) && (Z2_DIR_PIN > -1)
SET_OUTPUT(Z2_DIR_PIN);
Z2_DIR_INIT;
#endif
#endif
#if defined(E0_DIR_PIN) && E0_DIR_PIN > -1
SET_OUTPUT(E0_DIR_PIN);
E0_DIR_INIT;
#endif
#if defined(E1_DIR_PIN) && (E1_DIR_PIN > -1)
SET_OUTPUT(E1_DIR_PIN);
E1_DIR_INIT;
#endif
#if defined(E2_DIR_PIN) && (E2_DIR_PIN > -1)
SET_OUTPUT(E2_DIR_PIN);
E2_DIR_INIT;
#endif
#if defined(E3_DIR_PIN) && (E3_DIR_PIN > -1)
SET_OUTPUT(E3_DIR_PIN);
E3_DIR_INIT;
#endif
//Initialize Enable Pins - steppers default to disabled.
#if defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1
SET_OUTPUT(X_ENABLE_PIN);
if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
X_ENABLE_INIT;
if(!X_ENABLE_ON) X_ENABLE_WRITE(HIGH);
#endif
#if defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1
SET_OUTPUT(X2_ENABLE_PIN);
if(!X_ENABLE_ON) WRITE(X2_ENABLE_PIN,HIGH);
X2_ENABLE_INIT;
if(!X_ENABLE_ON) X2_ENABLE_WRITE(HIGH);
#endif
#if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1
SET_OUTPUT(Y_ENABLE_PIN);
if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
Y_ENABLE_INIT;
if(!Y_ENABLE_ON) Y_ENABLE_WRITE(HIGH);
#if defined(Y_DUAL_STEPPER_DRIVERS) && defined(Y2_ENABLE_PIN) && (Y2_ENABLE_PIN > -1)
SET_OUTPUT(Y2_ENABLE_PIN);
if(!Y_ENABLE_ON) WRITE(Y2_ENABLE_PIN,HIGH);
Y2_ENABLE_INIT;
if(!Y_ENABLE_ON) Y2_ENABLE_WRITE(HIGH);
#endif
#endif
#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
SET_OUTPUT(Z_ENABLE_PIN);
if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
Z_ENABLE_INIT;
if(!Z_ENABLE_ON) Z_ENABLE_WRITE(HIGH);
#if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_ENABLE_PIN) && (Z2_ENABLE_PIN > -1)
SET_OUTPUT(Z2_ENABLE_PIN);
if(!Z_ENABLE_ON) WRITE(Z2_ENABLE_PIN,HIGH);
Z2_ENABLE_INIT;
if(!Z_ENABLE_ON) Z2_ENABLE_WRITE(HIGH);
#endif
#endif
#if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1)
SET_OUTPUT(E0_ENABLE_PIN);
if(!E_ENABLE_ON) WRITE(E0_ENABLE_PIN,HIGH);
E0_ENABLE_INIT;
if(!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH);
#endif
#if defined(E1_ENABLE_PIN) && (E1_ENABLE_PIN > -1)
SET_OUTPUT(E1_ENABLE_PIN);
if(!E_ENABLE_ON) WRITE(E1_ENABLE_PIN,HIGH);
E1_ENABLE_INIT;
if(!E_ENABLE_ON) E1_ENABLE_WRITE(HIGH);
#endif
#if defined(E2_ENABLE_PIN) && (E2_ENABLE_PIN > -1)
SET_OUTPUT(E2_ENABLE_PIN);
if(!E_ENABLE_ON) WRITE(E2_ENABLE_PIN,HIGH);
E2_ENABLE_INIT;
if(!E_ENABLE_ON) E2_ENABLE_WRITE(HIGH);
#endif
#if defined(E3_ENABLE_PIN) && (E3_ENABLE_PIN > -1)
SET_OUTPUT(E3_ENABLE_PIN);
if(!E_ENABLE_ON) WRITE(E3_ENABLE_PIN,HIGH);
E3_ENABLE_INIT;
if(!E_ENABLE_ON) E3_ENABLE_WRITE(HIGH);
#endif
//endstops and pullups
@ -959,41 +962,51 @@ void st_init()
//Initialize Step Pins
#if defined(X_STEP_PIN) && (X_STEP_PIN > -1)
OUT_WRITE(X_STEP_PIN,INVERT_X_STEP_PIN);
X_STEP_INIT;
X_STEP_WRITE(INVERT_X_STEP_PIN);
disable_x();
#endif
#if defined(X2_STEP_PIN) && (X2_STEP_PIN > -1)
OUT_WRITE(X2_STEP_PIN,INVERT_X_STEP_PIN);
X2_STEP_INIT;
X2_STEP_WRITE(INVERT_X_STEP_PIN);
disable_x();
#endif
#if defined(Y_STEP_PIN) && (Y_STEP_PIN > -1)
OUT_WRITE(Y_STEP_PIN,INVERT_Y_STEP_PIN);
Y_STEP_INIT;
Y_STEP_WRITE(INVERT_Y_STEP_PIN);
#if defined(Y_DUAL_STEPPER_DRIVERS) && defined(Y2_STEP_PIN) && (Y2_STEP_PIN > -1)
OUT_WRITE(Y2_STEP_PIN,INVERT_Y_STEP_PIN);
Y2_STEP_INIT;
Y2_STEP_WRITE(INVERT_Y_STEP_PIN);
#endif
disable_y();
#endif
#if defined(Z_STEP_PIN) && (Z_STEP_PIN > -1)
OUT_WRITE(Z_STEP_PIN,INVERT_Z_STEP_PIN);
Z_STEP_INIT;
Z_STEP_WRITE(INVERT_Z_STEP_PIN);
#if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_STEP_PIN) && (Z2_STEP_PIN > -1)
OUT_WRITE(Z2_STEP_PIN,INVERT_Z_STEP_PIN);
Z2_STEP_INIT;
Z2_STEP_WRITE(INVERT_Z_STEP_PIN);
#endif
disable_z();
#endif
#if defined(E0_STEP_PIN) && (E0_STEP_PIN > -1)
OUT_WRITE(E0_STEP_PIN,INVERT_E_STEP_PIN);
E0_STEP_INIT;
E0_STEP_WRITE(INVERT_E_STEP_PIN);
disable_e0();
#endif
#if defined(E1_STEP_PIN) && (E1_STEP_PIN > -1)
OUT_WRITE(E1_STEP_PIN,INVERT_E_STEP_PIN);
E1_STEP_INIT;
E1_STEP_WRITE(INVERT_E_STEP_PIN);
disable_e1();
#endif
#if defined(E2_STEP_PIN) && (E2_STEP_PIN > -1)
OUT_WRITE(E2_STEP_PIN,INVERT_E_STEP_PIN);
E2_STEP_INIT;
E2_STEP_WRITE(INVERT_E_STEP_PIN);
disable_e2();
#endif
#if defined(E3_STEP_PIN) && (E3_STEP_PIN > -1)
OUT_WRITE(E3_STEP_PIN,INVERT_E_STEP_PIN);
E3_STEP_INIT;
E3_STEP_WRITE(INVERT_E_STEP_PIN);
disable_e3();
#endif
@ -1112,31 +1125,31 @@ void babystep(const uint8_t axis,const bool direction)
case X_AXIS:
{
enable_x();
uint8_t old_x_dir_pin= READ(X_DIR_PIN); //if dualzstepper, both point to same direction.
uint8_t old_x_dir_pin= X_DIR_READ; //if dualzstepper, both point to same direction.
//setup new step
WRITE(X_DIR_PIN,(INVERT_X_DIR)^direction);
X_DIR_WRITE((INVERT_X_DIR)^direction);
#ifdef DUAL_X_CARRIAGE
WRITE(X2_DIR_PIN,(INVERT_X_DIR)^direction);
X2_DIR_WRITE((INVERT_X_DIR)^direction);
#endif
//perform step
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
X_STEP_WRITE(!INVERT_X_STEP_PIN);
#ifdef DUAL_X_CARRIAGE
WRITE(X2_STEP_PIN, !INVERT_X_STEP_PIN);
X2_STEP_WRITE(!INVERT_X_STEP_PIN);
#endif
_delay_us(1U); // wait 1 microsecond
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
X_STEP_WRITE(INVERT_X_STEP_PIN);
#ifdef DUAL_X_CARRIAGE
WRITE(X2_STEP_PIN, INVERT_X_STEP_PIN);
X2_STEP_WRITE(INVERT_X_STEP_PIN);
#endif
//get old pin state back.
WRITE(X_DIR_PIN,old_x_dir_pin);
X_DIR_WRITE(old_x_dir_pin);
#ifdef DUAL_X_CARRIAGE
WRITE(X2_DIR_PIN,old_x_dir_pin);
X2_DIR_WRITE(old_x_dir_pin);
#endif
}
@ -1144,31 +1157,31 @@ void babystep(const uint8_t axis,const bool direction)
case Y_AXIS:
{
enable_y();
uint8_t old_y_dir_pin= READ(Y_DIR_PIN); //if dualzstepper, both point to same direction.
uint8_t old_y_dir_pin= Y_DIR_READ; //if dualzstepper, both point to same direction.
//setup new step
WRITE(Y_DIR_PIN,(INVERT_Y_DIR)^direction);
Y_DIR_WRITE((INVERT_Y_DIR)^direction);
#ifdef DUAL_Y_CARRIAGE
WRITE(Y2_DIR_PIN,(INVERT_Y_DIR)^direction);
Y2_DIR_WRITE((INVERT_Y_DIR)^direction);
#endif
//perform step
WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
#ifdef DUAL_Y_CARRIAGE
WRITE(Y2_STEP_PIN, !INVERT_Y_STEP_PIN);
Y2_STEP_WRITE( !INVERT_Y_STEP_PIN);
#endif
_delay_us(1U); // wait 1 microsecond
WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
Y_STEP_WRITE(INVERT_Y_STEP_PIN);
#ifdef DUAL_Y_CARRIAGE
WRITE(Y2_STEP_PIN, INVERT_Y_STEP_PIN);
Y2_STEP_WRITE(INVERT_Y_STEP_PIN);
#endif
//get old pin state back.
WRITE(Y_DIR_PIN,old_y_dir_pin);
Y_DIR_WRITE(old_y_dir_pin);
#ifdef DUAL_Y_CARRIAGE
WRITE(Y2_DIR_PIN,old_y_dir_pin);
Y2_DIR_WRITE(old_y_dir_pin);
#endif
}
@ -1178,29 +1191,29 @@ void babystep(const uint8_t axis,const bool direction)
case Z_AXIS:
{
enable_z();
uint8_t old_z_dir_pin= READ(Z_DIR_PIN); //if dualzstepper, both point to same direction.
uint8_t old_z_dir_pin= Z_DIR_READ; //if dualzstepper, both point to same direction.
//setup new step
WRITE(Z_DIR_PIN,(INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z);
Z_DIR_WRITE((INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z);
#ifdef Z_DUAL_STEPPER_DRIVERS
WRITE(Z2_DIR_PIN,(INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z);
Z2_DIR_WRITE((INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z);
#endif
//perform step
WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
Z_STEP_WRITE(!INVERT_Z_STEP_PIN);
#ifdef Z_DUAL_STEPPER_DRIVERS
WRITE(Z2_STEP_PIN, !INVERT_Z_STEP_PIN);
Z2_STEP_WRITE( !INVERT_Z_STEP_PIN);
#endif
_delay_us(1U); // wait 1 microsecond
WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN);
Z_STEP_WRITE( INVERT_Z_STEP_PIN);
#ifdef Z_DUAL_STEPPER_DRIVERS
WRITE(Z2_STEP_PIN, INVERT_Z_STEP_PIN);
Z2_STEP_WRITE(INVERT_Z_STEP_PIN);
#endif
//get old pin state back.
WRITE(Z_DIR_PIN,old_z_dir_pin);
Z_DIR_WRITE(old_z_dir_pin);
#ifdef Z_DUAL_STEPPER_DRIVERS
WRITE(Z2_DIR_PIN,old_z_dir_pin);
Z2_DIR_WRITE(old_z_dir_pin);
#endif
}
@ -1211,29 +1224,29 @@ void babystep(const uint8_t axis,const bool direction)
enable_x();
enable_y();
enable_z();
uint8_t old_x_dir_pin= READ(X_DIR_PIN);
uint8_t old_y_dir_pin= READ(Y_DIR_PIN);
uint8_t old_z_dir_pin= READ(Z_DIR_PIN);
uint8_t old_x_dir_pin= X_DIR_READ;
uint8_t old_y_dir_pin= Y_DIR_READ;
uint8_t old_z_dir_pin= Z_DIR_READ;
//setup new step
WRITE(X_DIR_PIN,(INVERT_X_DIR)^direction^BABYSTEP_INVERT_Z);
WRITE(Y_DIR_PIN,(INVERT_Y_DIR)^direction^BABYSTEP_INVERT_Z);
WRITE(Z_DIR_PIN,(INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z);
X_DIR_WRITE((INVERT_X_DIR)^direction^BABYSTEP_INVERT_Z);
Y_DIR_WRITE((INVERT_Y_DIR)^direction^BABYSTEP_INVERT_Z);
Z_DIR_WRITE((INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z);
//perform step
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
X_STEP_WRITE( !INVERT_X_STEP_PIN);
Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
Z_STEP_WRITE(!INVERT_Z_STEP_PIN);
_delay_us(1U); // wait 1 microsecond
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN);
X_STEP_WRITE(INVERT_X_STEP_PIN);
Y_STEP_WRITE(INVERT_Y_STEP_PIN);
Z_STEP_WRITE(INVERT_Z_STEP_PIN);
//get old pin state back.
WRITE(X_DIR_PIN,old_x_dir_pin);
WRITE(Y_DIR_PIN,old_y_dir_pin);
WRITE(Z_DIR_PIN,old_z_dir_pin);
X_DIR_WRITE(old_x_dir_pin);
Y_DIR_WRITE(old_y_dir_pin);
Z_DIR_WRITE(old_z_dir_pin);
}
break;
@ -1370,4 +1383,3 @@ void microstep_readings()
SERIAL_PROTOCOLLN( digitalRead(E1_MS2_PIN));
#endif
}

View file

@ -22,30 +22,31 @@
#define stepper_h
#include "planner.h"
#include "stepper_indirection.h"
#if EXTRUDERS > 3
#define WRITE_E_STEP(v) { if(current_block->active_extruder == 3) { WRITE(E3_STEP_PIN, v); } else { if(current_block->active_extruder == 2) { WRITE(E2_STEP_PIN, v); } else { if(current_block->active_extruder == 1) { WRITE(E1_STEP_PIN, v); } else { WRITE(E0_STEP_PIN, v); }}}}
#define NORM_E_DIR() { if(current_block->active_extruder == 3) { WRITE(E3_DIR_PIN, !INVERT_E3_DIR); } else { if(current_block->active_extruder == 2) { WRITE(E2_DIR_PIN, !INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, !INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); }}}}
#define REV_E_DIR() { if(current_block->active_extruder == 3) { WRITE(E3_DIR_PIN, INVERT_E3_DIR); } else { if(current_block->active_extruder == 2) { WRITE(E2_DIR_PIN, INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, INVERT_E0_DIR); }}}}
#define WRITE_E_STEP(v) { if(current_block->active_extruder == 3) { E3_STEP_WRITE(v); } else { if(current_block->active_extruder == 2) { E2_STEP_WRITE(v); } else { if(current_block->active_extruder == 1) { E1_STEP_WRITE(v); } else { E0_STEP_WRITE(v); }}}}
#define NORM_E_DIR() { if(current_block->active_extruder == 3) { E3_DIR_WRITE( !INVERT_E3_DIR); } else { if(current_block->active_extruder == 2) { E2_DIR_WRITE(!INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { E1_DIR_WRITE(!INVERT_E1_DIR); } else { E0_DIR_WRITE(!INVERT_E0_DIR); }}}}
#define REV_E_DIR() { if(current_block->active_extruder == 3) { E3_DIR_WRITE(INVERT_E3_DIR); } else { if(current_block->active_extruder == 2) { E2_DIR_WRITE(INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { E1_DIR_WRITE(INVERT_E1_DIR); } else { E0_DIR_WRITE(INVERT_E0_DIR); }}}}
#elif EXTRUDERS > 2
#define WRITE_E_STEP(v) { if(current_block->active_extruder == 2) { WRITE(E2_STEP_PIN, v); } else { if(current_block->active_extruder == 1) { WRITE(E1_STEP_PIN, v); } else { WRITE(E0_STEP_PIN, v); }}}
#define NORM_E_DIR() { if(current_block->active_extruder == 2) { WRITE(E2_DIR_PIN, !INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, !INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); }}}
#define REV_E_DIR() { if(current_block->active_extruder == 2) { WRITE(E2_DIR_PIN, INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, INVERT_E0_DIR); }}}
#define WRITE_E_STEP(v) { if(current_block->active_extruder == 2) { E2_STEP_WRITE(v); } else { if(current_block->active_extruder == 1) { E1_STEP_WRITE(v); } else { E0_STEP_WRITE(v); }}}
#define NORM_E_DIR() { if(current_block->active_extruder == 2) { E2_DIR_WRITE(!INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { E1_DIR_WRITE(!INVERT_E1_DIR); } else { E0_DIR_WRITE(!INVERT_E0_DIR); }}}
#define REV_E_DIR() { if(current_block->active_extruder == 2) { E2_DIR_WRITE(INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { E1_DIR_WRITE(INVERT_E1_DIR); } else { E0_DIR_WRITE(INVERT_E0_DIR); }}}
#elif EXTRUDERS > 1
#ifndef DUAL_X_CARRIAGE
#define WRITE_E_STEP(v) { if(current_block->active_extruder == 1) { WRITE(E1_STEP_PIN, v); } else { WRITE(E0_STEP_PIN, v); }}
#define NORM_E_DIR() { if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, !INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); }}
#define REV_E_DIR() { if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, INVERT_E0_DIR); }}
#define WRITE_E_STEP(v) { if(current_block->active_extruder == 1) { E1_STEP_WRITE(v); } else { E0_STEP_WRITE(v); }}
#define NORM_E_DIR() { if(current_block->active_extruder == 1) { E1_DIR_WRITE(!INVERT_E1_DIR); } else { E0_DIR_WRITE(!INVERT_E0_DIR); }}
#define REV_E_DIR() { if(current_block->active_extruder == 1) { E1_DIR_WRITE(INVERT_E1_DIR); } else { E0_DIR_WRITE(INVERT_E0_DIR); }}
#else
extern bool extruder_duplication_enabled;
#define WRITE_E_STEP(v) { if(extruder_duplication_enabled) { WRITE(E0_STEP_PIN, v); WRITE(E1_STEP_PIN, v); } else if(current_block->active_extruder == 1) { WRITE(E1_STEP_PIN, v); } else { WRITE(E0_STEP_PIN, v); }}
#define NORM_E_DIR() { if(extruder_duplication_enabled) { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); WRITE(E1_DIR_PIN, !INVERT_E1_DIR); } else if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, !INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); }}
#define REV_E_DIR() { if(extruder_duplication_enabled) { WRITE(E0_DIR_PIN, INVERT_E0_DIR); WRITE(E1_DIR_PIN, INVERT_E1_DIR); } else if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, INVERT_E0_DIR); }}
#define WRITE_E_STEP(v) { if(extruder_duplication_enabled) { E0_STEP_WRITE(v); E1_STEP_WRITE(v); } else if(current_block->active_extruder == 1) { E1_STEP_WRITE(v); } else { E0_STEP_WRITE(v); }}
#define NORM_E_DIR() { if(extruder_duplication_enabled) { E0_DIR_WRITE(!INVERT_E0_DIR); E1_DIR_WRITE(!INVERT_E1_DIR); } else if(current_block->active_extruder == 1) { E1_DIR_WRITE(!INVERT_E1_DIR); } else { E0_DIR_WRITE(!INVERT_E0_DIR); }}
#define REV_E_DIR() { if(extruder_duplication_enabled) { E0_DIR_WRITE(INVERT_E0_DIR); E1_DIR_WRITE(INVERT_E1_DIR); } else if(current_block->active_extruder == 1) { E1_DIR_WRITE(INVERT_E1_DIR); } else { E0_DIR_WRITE(INVERT_E0_DIR); }}
#endif
#else
#define WRITE_E_STEP(v) WRITE(E0_STEP_PIN, v)
#define NORM_E_DIR() WRITE(E0_DIR_PIN, !INVERT_E0_DIR)
#define REV_E_DIR() WRITE(E0_DIR_PIN, INVERT_E0_DIR)
#define WRITE_E_STEP(v) E0_STEP_WRITE(v)
#define NORM_E_DIR() E0_DIR_WRITE(!INVERT_E0_DIR)
#define REV_E_DIR() E0_DIR_WRITE(INVERT_E0_DIR)
#endif
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
@ -100,6 +101,4 @@ void microstep_readings();
void babystep(const uint8_t axis,const bool direction); // perform a short step with a single stepper motor, outside of any convention
#endif
#endif

View file

@ -0,0 +1,224 @@
/*
stepper_indirection.c - stepper motor driver indirection
to allow some stepper functions to be done via SPI/I2c instead of direct pin manipulation
Part of Marlin
Copyright (c) 2015 Dominik Wenger
Marlin is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Marlin is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Marlin. If not, see <http://www.gnu.org/licenses/>.
*/
#include "stepper_indirection.h"
#include "Configuration.h"
#ifdef HAVE_TMCDRIVER
#include <SPI.h>
#include <TMC26XStepper.h>
#endif
// Stepper objects of TMC steppers used
#ifdef X_IS_TMC
TMC26XStepper stepperX(200,X_ENABLE_PIN,X_STEP_PIN,X_DIR_PIN,X_MAX_CURRENT,X_SENSE_RESISTOR);
#endif
#ifdef X2_IS_TMC
TMC26XStepper stepperX2(200,X2_ENABLE_PIN,X2_STEP_PIN,X2_DIR_PIN,X2_MAX_CURRENT,X2_SENSE_RESISTOR);
#endif
#ifdef Y_IS_TMC
TMC26XStepper stepperY(200,Y_ENABLE_PIN,Y_STEP_PIN,Y_DIR_PIN,Y_MAX_CURRENT,Y_SENSE_RESISTOR);
#endif
#ifdef Y2_IS_TMC
TMC26XStepper stepperY2(200,Y2_ENABLE_PIN,Y2_STEP_PIN,Y2_DIR_PIN,Y2_MAX_CURRENT,Y2_SENSE_RESISTOR);
#endif
#ifdef Z_IS_TMC
TMC26XStepper stepperZ(200,Z_ENABLE_PIN,Z_STEP_PIN,Z_DIR_PIN,Z_MAX_CURRENT,Z_SENSE_RESISTOR);
#endif
#ifdef Z2_IS_TMC
TMC26XStepper stepperZ2(200,Z2_ENABLE_PIN,Z2_STEP_PIN,Z2_DIR_PIN,Z2_MAX_CURRENT,Z2_SENSE_RESISTOR);
#endif
#ifdef E0_IS_TMC
TMC26XStepper stepperE0(200,E0_ENABLE_PIN,E0_STEP_PIN,E0_DIR_PIN,E0_MAX_CURRENT,E0_SENSE_RESISTOR);
#endif
#ifdef E1_IS_TMC
TMC26XStepper stepperE1(200,E1_ENABLE_PIN,E1_STEP_PIN,E1_DIR_PIN,E1_MAX_CURRENT,E1_SENSE_RESISTOR);
#endif
#ifdef E2_IS_TMC
TMC26XStepper stepperE2(200,E2_ENABLE_PIN,E2_STEP_PIN,E2_DIR_PIN,E2_MAX_CURRENT,E2_SENSE_RESISTOR);
#endif
#ifdef E3_IS_TMC
TMC26XStepper stepperE3(200,E3_ENABLE_PIN,E3_STEP_PIN,E3_DIR_PIN,E3_MAX_CURRENT,E3_SENSE_RESISTOR);
#endif
#ifdef HAVE_TMCDRIVER
void tmc_init()
{
#ifdef X_IS_TMC
stepperX.setMicrosteps(X_MICROSTEPS);
stepperX.start();
#endif
#ifdef X2_IS_TMC
stepperX2.setMicrosteps(X2_MICROSTEPS);
stepperX2.start();
#endif
#ifdef Y_IS_TMC
stepperY.setMicrosteps(Y_MICROSTEPS);
stepperY.start();
#endif
#ifdef Y2_IS_TMC
stepperY2.setMicrosteps(Y2_MICROSTEPS);
stepperY2.start();
#endif
#ifdef Z_IS_TMC
stepperZ.setMicrosteps(Z_MICROSTEPS);
stepperZ.start();
#endif
#ifdef Z2_IS_TMC
stepperZ2.setMicrosteps(Z2_MICROSTEPS);
stepperZ2.start();
#endif
#ifdef E0_IS_TMC
stepperE0.setMicrosteps(E0_MICROSTEPS);
stepperE0.start();
#endif
#ifdef E1_IS_TMC
stepperE1.setMicrosteps(E1_MICROSTEPS);
stepperE1.start();
#endif
#ifdef E2_IS_TMC
stepperE2.setMicrosteps(E2_MICROSTEPS);
stepperE2.start();
#endif
#ifdef E3_IS_TMC
stepperE3.setMicrosteps(E3_MICROSTEPS);
stepperE3.start();
#endif
}
#endif
// L6470 Driver objects and inits
#ifdef HAVE_L6470DRIVER
#include <SPI.h>
#include <L6470.h>
#endif
// L6470 Stepper objects
#ifdef X_IS_L6470
L6470 stepperX(X_ENABLE_PIN);
#endif
#ifdef X2_IS_L6470
L6470 stepperX2(X2_ENABLE_PIN);
#endif
#ifdef Y_IS_L6470
L6470 stepperY(Y_ENABLE_PIN);
#endif
#ifdef Y2_IS_L6470
L6470 stepperY2(Y2_ENABLE_PIN);
#endif
#ifdef Z_IS_L6470
L6470 stepperZ(Z_ENABLE_PIN);
#endif
#ifdef Z2_IS_L6470
L6470 stepperZ2(Z2_ENABLE_PIN);
#endif
#ifdef E0_IS_L6470
L6470 stepperE0(E0_ENABLE_PIN);
#endif
#ifdef E1_IS_L6470
L6470 stepperE1(E1_ENABLE_PIN);
#endif
#ifdef E2_IS_L6470
L6470 stepperE2(E2_ENABLE_PIN);
#endif
#ifdef E3_IS_L6470
L6470 stepperE3(E3_ENABLE_PIN);
#endif
// init routine
#ifdef HAVE_L6470DRIVER
void L6470_init()
{
#ifdef X_IS_L6470
stepperX.init(X_K_VAL);
stepperX.softFree();
stepperX.setMicroSteps(X_MICROSTEPS);
stepperX.setOverCurrent(X_OVERCURRENT); //set overcurrent protection
stepperX.setStallCurrent(X_STALLCURRENT);
#endif
#ifdef X2_IS_L6470
stepperX2.init(X2_K_VAL);
stepperX2.softFree();
stepperX2.setMicroSteps(X2_MICROSTEPS);
stepperX2.setOverCurrent(X2_OVERCURRENT); //set overcurrent protection
stepperX2.setStallCurrent(X2_STALLCURRENT);
#endif
#ifdef Y_IS_L6470
stepperY.init(Y_K_VAL);
stepperY.softFree();
stepperY.setMicroSteps(Y_MICROSTEPS);
stepperY.setOverCurrent(Y_OVERCURRENT); //set overcurrent protection
stepperY.setStallCurrent(Y_STALLCURRENT);
#endif
#ifdef Y2_IS_L6470
stepperY2.init(Y2_K_VAL);
stepperY2.softFree();
stepperY2.setMicroSteps(Y2_MICROSTEPS);
stepperY2.setOverCurrent(Y2_OVERCURRENT); //set overcurrent protection
stepperY2.setStallCurrent(Y2_STALLCURRENT);
#endif
#ifdef Z_IS_L6470
stepperZ.init(Z_K_VAL);
stepperZ.softFree();
stepperZ.setMicroSteps(Z_MICROSTEPS);
stepperZ.setOverCurrent(Z_OVERCURRENT); //set overcurrent protection
stepperZ.setStallCurrent(Z_STALLCURRENT);
#endif
#ifdef Z2_IS_L6470
stepperZ2.init(Z2_K_VAL);
stepperZ2.softFree();
stepperZ2.setMicroSteps(Z2_MICROSTEPS);
stepperZ2.setOverCurrent(Z2_OVERCURRENT); //set overcurrent protection
stepperZ2.setStallCurrent(Z2_STALLCURRENT);
#endif
#ifdef E0_IS_L6470
stepperE0.init(E0_K_VAL);
stepperE0.softFree();
stepperE0.setMicroSteps(E0_MICROSTEPS);
stepperE0.setOverCurrent(E0_OVERCURRENT); //set overcurrent protection
stepperE0.setStallCurrent(E0_STALLCURRENT);
#endif
#ifdef E1_IS_L6470
stepperE1.init(E1_K_VAL);
stepperE1.softFree();
stepperE1.setMicroSteps(E1_MICROSTEPS);
stepperE1.setOverCurrent(E1_OVERCURRENT); //set overcurrent protection
stepperE1.setStallCurrent(E1_STALLCURRENT);
#endif
#ifdef E2_IS_L6470
stepperE2.init(E2_K_VAL);
stepperE2.softFree();
stepperE2.setMicroSteps(E2_MICROSTEPS);
stepperE2.setOverCurrent(E2_OVERCURRENT); //set overcurrent protection
stepperE2.setStallCurrent(E2_STALLCURRENT);
#endif
#ifdef E3_IS_L6470
stepperE3.init(E3_K_VAL);
stepperE3.softFree();
stepperE3.setMicroSteps(E3_MICROSTEPS);
stepperE3.setOverCurrent(E3_OVERCURRENT); //set overcurrent protection
stepperE3.setStallCurrent(E3_STALLCURRENT);
#endif
}
#endif

View file

@ -0,0 +1,492 @@
/*
stepper_indirection.h - stepper motor driver indirection macros
to allow some stepper functions to be done via SPI/I2c instead of direct pin manipulation
Part of Marlin
Copyright (c) 2015 Dominik Wenger
Marlin is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Marlin is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Marlin. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef STEPPER_INDIRECTION_H
#define STEPPER_INDIRECTION_H
// X motor
#define X_STEP_INIT SET_OUTPUT(X_STEP_PIN)
#define X_STEP_WRITE(STATE) WRITE(X_STEP_PIN,STATE)
#define X_STEP_READ READ(X_STEP_PIN)
#define X_DIR_INIT SET_OUTPUT(X_DIR_PIN)
#define X_DIR_WRITE(STATE) WRITE(X_DIR_PIN,STATE)
#define X_DIR_READ READ(X_DIR_PIN)
#define X_ENABLE_INIT SET_OUTPUT(X_ENABLE_PIN)
#define X_ENABLE_WRITE(STATE) WRITE(X_ENABLE_PIN,STATE)
#define X_ENABLE_READ READ(X_ENABLE_PIN)
// X2 motor
#define X2_STEP_INIT SET_OUTPUT(X2_STEP_PIN)
#define X2_STEP_WRITE(STATE) WRITE(X2_STEP_PIN,STATE)
#define X2_STEP_READ READ(X2_STEP_PIN)
#define X2_DIR_INIT SET_OUTPUT(X2_DIR_PIN)
#define X2_DIR_WRITE(STATE) WRITE(X2_DIR_PIN,STATE)
#define X2_DIR_READ READ(X_DIR_PIN)
#define X2_ENABLE_INIT SET_OUTPUT(X2_ENABLE_PIN)
#define X2_ENABLE_WRITE(STATE) WRITE(X2_ENABLE_PIN,STATE)
#define X2_ENABLE_READ READ(X_ENABLE_PIN)
// Y motor
#define Y_STEP_INIT SET_OUTPUT(Y_STEP_PIN)
#define Y_STEP_WRITE(STATE) WRITE(Y_STEP_PIN,STATE)
#define Y_STEP_READ READ(Y_STEP_PIN)
#define Y_DIR_INIT SET_OUTPUT(Y_DIR_PIN)
#define Y_DIR_WRITE(STATE) WRITE(Y_DIR_PIN,STATE)
#define Y_DIR_READ READ(Y_DIR_PIN)
#define Y_ENABLE_INIT SET_OUTPUT(Y_ENABLE_PIN)
#define Y_ENABLE_WRITE(STATE) WRITE(Y_ENABLE_PIN,STATE)
#define Y_ENABLE_READ READ(Y_ENABLE_PIN)
// Y2 motor
#define Y2_STEP_INIT SET_OUTPUT(Y2_STEP_PIN)
#define Y2_STEP_WRITE(STATE) WRITE(Y2_STEP_PIN,STATE)
#define Y2_STEP_READ READ(Y2_STEP_PIN)
#define Y2_DIR_INIT SET_OUTPUT(Y2_DIR_PIN)
#define Y2_DIR_WRITE(STATE) WRITE(Y2_DIR_PIN,STATE)
#define Y2_DIR_READ READ(Y2_DIR_PIN)
#define Y2_ENABLE_INIT SET_OUTPUT(Y2_ENABLE_PIN)
#define Y2_ENABLE_WRITE(STATE) WRITE(Y2_ENABLE_PIN,STATE)
#define Y2_ENABLE_READ READ(Y2_ENABLE_PIN)
// Z motor
#define Z_STEP_INIT SET_OUTPUT(Z_STEP_PIN)
#define Z_STEP_WRITE(STATE) WRITE(Z_STEP_PIN,STATE)
#define Z_STEP_READ READ(Z_STEP_PIN)
#define Z_DIR_INIT SET_OUTPUT(Z_DIR_PIN)
#define Z_DIR_WRITE(STATE) WRITE(Z_DIR_PIN,STATE)
#define Z_DIR_READ READ(Z_DIR_PIN)
#define Z_ENABLE_INIT SET_OUTPUT(Z_ENABLE_PIN)
#define Z_ENABLE_WRITE(STATE) WRITE(Z_ENABLE_PIN,STATE)
#define Z_ENABLE_READ READ(Z_ENABLE_PIN)
// Z2 motor
#define Z2_STEP_INIT SET_OUTPUT(Z2_STEP_PIN)
#define Z2_STEP_WRITE(STATE) WRITE(Z2_STEP_PIN,STATE)
#define Z2_STEP_READ READ(Z2_STEP_PIN)
#define Z2_DIR_INIT SET_OUTPUT(Z2_DIR_PIN)
#define Z2_DIR_WRITE(STATE) WRITE(Z2_DIR_PIN,STATE)
#define Z2_DIR_READ READ(Z2_DIR_PIN)
#define Z2_ENABLE_INIT SET_OUTPUT(Z2_ENABLE_PIN)
#define Z2_ENABLE_WRITE(STATE) WRITE(Z2_ENABLE_PIN,STATE)
#define Z2_ENABLE_READ READ(Z2_ENABLE_PIN)
// E0 motor
#define E0_STEP_INIT SET_OUTPUT(E0_STEP_PIN)
#define E0_STEP_WRITE(STATE) WRITE(E0_STEP_PIN,STATE)
#define E0_STEP_READ READ(E0_STEP_PIN)
#define E0_DIR_INIT SET_OUTPUT(E0_DIR_PIN)
#define E0_DIR_WRITE(STATE) WRITE(E0_DIR_PIN,STATE)
#define E0_DIR_READ READ(E0_DIR_PIN)
#define E0_ENABLE_INIT SET_OUTPUT(E0_ENABLE_PIN)
#define E0_ENABLE_WRITE(STATE) WRITE(E0_ENABLE_PIN,STATE)
#define E0_ENABLE_READ READ(E0_ENABLE_PIN)
// E1 motor
#define E1_STEP_INIT SET_OUTPUT(E1_STEP_PIN)
#define E1_STEP_WRITE(STATE) WRITE(E1_STEP_PIN,STATE)
#define E1_STEP_READ READ(E1_STEP_PIN)
#define E1_DIR_INIT SET_OUTPUT(E1_DIR_PIN)
#define E1_DIR_WRITE(STATE) WRITE(E1_DIR_PIN,STATE)
#define E1_DIR_READ READ(E1_DIR_PIN)
#define E1_ENABLE_INIT SET_OUTPUT(E1_ENABLE_PIN)
#define E1_ENABLE_WRITE(STATE) WRITE(E1_ENABLE_PIN,STATE)
#define E1_ENABLE_READ READ(E1_ENABLE_PIN)
// E2 motor
#define E2_STEP_INIT SET_OUTPUT(E2_STEP_PIN)
#define E2_STEP_WRITE(STATE) WRITE(E2_STEP_PIN,STATE)
#define E2_STEP_READ READ(E2_STEP_PIN)
#define E2_DIR_INIT SET_OUTPUT(E2_DIR_PIN)
#define E2_DIR_WRITE(STATE) WRITE(E2_DIR_PIN,STATE)
#define E2_DIR_READ READ(E2_DIR_PIN)
#define E2_ENABLE_INIT SET_OUTPUT(E2_ENABLE_PIN)
#define E2_ENABLE_WRITE(STATE) WRITE(E2_ENABLE_PIN,STATE)
#define E2_ENABLE_READ READ(E2_ENABLE_PIN)
// E3 motor
#define E3_STEP_INIT SET_OUTPUT(E3_STEP_PIN)
#define E3_STEP_WRITE(STATE) WRITE(E3_STEP_PIN,STATE)
#define E3_STEP_READ READ(E3_STEP_PIN)
#define E3_DIR_INIT SET_OUTPUT(E3_DIR_PIN)
#define E3_DIR_WRITE(STATE) WRITE(E3_DIR_PIN,STATE)
#define E3_DIR_READ READ(E3_DIR_PIN)
#define E3_ENABLE_INIT SET_OUTPUT(E3_ENABLE_PIN)
#define E3_ENABLE_WRITE(STATE) WRITE(E3_ENABLE_PIN,STATE)
#define E3_ENABLE_READ READ(E3_ENABLE_PIN)
//////////////////////////////////
// Pin redefines for TMC drivers.
// TMC26X drivers have step and dir on normal pins, but everything else via SPI
//////////////////////////////////
#ifdef HAVE_TMCDRIVER
#include <SPI.h>
#include <TMC26XStepper.h>
void tmc_init();
#ifdef X_IS_TMC
extern TMC26XStepper stepperX;
#undef X_ENABLE_INIT
#define X_ENABLE_INIT ((void)0)
#undef X_ENABLE_WRITE
#define X_ENABLE_WRITE(STATE) stepperX.setEnabled(STATE)
#undef X_ENABLE_READ
#define X_ENABLE_READ stepperX.isEnabled()
#endif
#ifdef X2_IS_TMC
extern TMC26XStepper stepperX2;
#undef X2_ENABLE_INIT
#define X2_ENABLE_INIT ((void)0)
#undef X2_ENABLE_WRITE
#define X2_ENABLE_WRITE(STATE) stepperX2.setEnabled(STATE)
#undef X2_ENABLE_READ
#define X2_ENABLE_READ stepperX2.isEnabled()
#endif
#ifdef Y_IS_TMC
extern TMC26XStepper stepperY;
#undef Y_ENABLE_INIT
#define Y_ENABLE_INIT ((void)0)
#undef Y_ENABLE_WRITE
#define Y_ENABLE_WRITE(STATE) stepperY.setEnabled(STATE)
#undef Y_ENABLE_READ
#define Y_ENABLE_READ stepperY.isEnabled()
#endif
#ifdef Y2_IS_TMC
extern TMC26XStepper stepperY2;
#undef Y2_ENABLE_INIT
#define Y2_ENABLE_INIT ((void)0)
#undef Y2_ENABLE_WRITE
#define Y2_ENABLE_WRITE(STATE) stepperY2.setEnabled(STATE)
#undef Y2_ENABLE_READ
#define Y2_ENABLE_READ stepperY2.isEnabled()
#endif
#ifdef Z_IS_TMC
extern TMC26XStepper stepperZ;
#undef Z_ENABLE_INIT
#define Z_ENABLE_INIT ((void)0)
#undef Z_ENABLE_WRITE
#define Z_ENABLE_WRITE(STATE) stepperZ.setEnabled(STATE)
#undef Z_ENABLE_READ
#define Z_ENABLE_READ stepperZ.isEnabled()
#endif
#ifdef Z2_IS_TMC
extern TMC26XStepper stepperZ2;
#undef Z2_ENABLE_INIT
#define Z2_ENABLE_INIT ((void)0)
#undef Z2_ENABLE_WRITE
#define Z2_ENABLE_WRITE(STATE) stepperZ2.setEnabled(STATE)
#undef Z2_ENABLE_READ
#define Z2_ENABLE_READ stepperZ2.isEnabled()
#endif
#ifdef E0_IS_TMC
extern TMC26XStepper stepperE0;
#undef E0_ENABLE_INIT
#define E0_ENABLE_INIT ((void)0)
#undef E0_ENABLE_WRITE
#define E0_ENABLE_WRITE(STATE) stepperE0.setEnabled(STATE)
#undef E0_ENABLE_READ
#define E0_ENABLE_READ stepperE0.isEnabled()
#endif
#ifdef E1_IS_TMC
extern TMC26XStepper stepperE1;
#undef E1_ENABLE_INIT
#define E1_ENABLE_INIT ((void)0)
#undef E1_ENABLE_WRITE
#define E1_ENABLE_WRITE(STATE) stepperE1.setEnabled(STATE)
#undef E1_ENABLE_READ
#define E1_ENABLE_READ stepperE1.isEnabled()
#endif
#ifdef E2_IS_TMC
extern TMC26XStepper stepperE2;
#undef E2_ENABLE_INIT
#define E2_ENABLE_INIT ((void)0)
#undef E2_ENABLE_WRITE
#define E2_ENABLE_WRITE(STATE) stepperE2.setEnabled(STATE)
#undef E2_ENABLE_READ
#define E2_ENABLE_READ stepperE2.isEnabled()
#endif
#ifdef E3_IS_TMC
extern TMC26XStepper stepperE3;
#undef E3_ENABLE_INIT
#define E3_ENABLE_INIT ((void)0)
#undef E3_ENABLE_WRITE
#define E3_ENABLE_WRITE(STATE) stepperE3.setEnabled(STATE)
#undef E3_ENABLE_READ
#define E3_ENABLE_READ stepperE3.isEnabled()
#endif
#endif // HAVE_TMCDRIVER
//////////////////////////////////
// Pin redefines for L6470 drivers.
// L640 drivers have step on normal pins, but dir and everything else via SPI
//////////////////////////////////
#ifdef HAVE_L6470DRIVER
#include <SPI.h>
#include <L6470.h>
void L6470_init();
#ifdef X_IS_L6470
extern L6470 stepperX;
#undef X_ENABLE_INIT
#define X_ENABLE_INIT ((void)0)
#undef X_ENABLE_WRITE
#define X_ENABLE_WRITE(STATE) {if(STATE) stepperX.Step_Clock(stepperX.getStatus() & STATUS_HIZ); else stepperX.softFree();}
#undef X_ENABLE_READ
#define X_ENABLE_READ (stepperX.getStatus() & STATUS_HIZ)
#undef X_DIR_INIT
#define X_DIR_INIT ((void)0)
#undef X_DIR_WRITE
#define X_DIR_WRITE(STATE) stepperX.Step_Clock(STATE)
#undef X_DIR_READ
#define X_DIR_READ (stepperX.getStatus() & STATUS_DIR)
#endif
#ifdef X2_IS_L6470
extern L6470 stepperX2;
#undef X2_ENABLE_INIT
#define X2_ENABLE_INIT ((void)0)
#undef X2_ENABLE_WRITE
#define X2_ENABLE_WRITE(STATE) (if(STATE) stepperX2.Step_Clock(stepperX2.getStatus() & STATUS_HIZ); else stepperX2.softFree();)
#undef X2_ENABLE_READ
#define X2_ENABLE_READ (stepperX2.getStatus() & STATUS_HIZ)
#undef X2_DIR_INIT
#define X2_DIR_INIT ((void)0)
#undef X2_DIR_WRITE
#define X2_DIR_WRITE(STATE) stepperX2.Step_Clock(STATE)
#undef X2_DIR_READ
#define X2_DIR_READ (stepperX2.getStatus() & STATUS_DIR)
#endif
#ifdef Y_IS_L6470
extern L6470 stepperY;
#undef Y_ENABLE_INIT
#define Y_ENABLE_INIT ((void)0)
#undef Y_ENABLE_WRITE
#define Y_ENABLE_WRITE(STATE) (if(STATE) stepperY.Step_Clock(stepperY.getStatus() & STATUS_HIZ); else stepperY.softFree();)
#undef Y_ENABLE_READ
#define Y_ENABLE_READ (stepperY.getStatus() & STATUS_HIZ)
#undef Y_DIR_INIT
#define Y_DIR_INIT ((void)0)
#undef Y_DIR_WRITE
#define Y_DIR_WRITE(STATE) stepperY.Step_Clock(STATE)
#undef Y_DIR_READ
#define Y_DIR_READ (stepperY.getStatus() & STATUS_DIR)
#endif
#ifdef Y2_IS_L6470
extern L6470 stepperY2;
#undef Y2_ENABLE_INIT
#define Y2_ENABLE_INIT ((void)0)
#undef Y2_ENABLE_WRITE
#define Y2_ENABLE_WRITE(STATE) (if(STATE) stepperY2.Step_Clock(stepperY2.getStatus() & STATUS_HIZ); else stepperY2.softFree();)
#undef Y2_ENABLE_READ
#define Y2_ENABLE_READ (stepperY2.getStatus() & STATUS_HIZ)
#undef Y2_DIR_INIT
#define Y2_DIR_INIT ((void)0)
#undef Y2_DIR_WRITE
#define Y2_DIR_WRITE(STATE) stepperY2.Step_Clock(STATE)
#undef Y2_DIR_READ
#define Y2_DIR_READ (stepperY2.getStatus() & STATUS_DIR)
#endif
#ifdef Z_IS_L6470
extern L6470 stepperZ;
#undef Z_ENABLE_INIT
#define Z_ENABLE_INIT ((void)0)
#undef Z_ENABLE_WRITE
#define Z_ENABLE_WRITE(STATE) (if(STATE) stepperZ.Step_Clock(stepperZ.getStatus() & STATUS_HIZ); else stepperZ.softFree();)
#undef Z_ENABLE_READ
#define Z_ENABLE_READ (stepperZ.getStatus() & STATUS_HIZ)
#undef Z_DIR_INIT
#define Z_DIR_INIT ((void)0)
#undef Z_DIR_WRITE
#define Z_DIR_WRITE(STATE) stepperZ.Step_Clock(STATE)
#undef Y_DIR_READ
#define Y_DIR_READ (stepperZ.getStatus() & STATUS_DIR)
#endif
#ifdef Z2_IS_L6470
extern L6470 stepperZ2;
#undef Z2_ENABLE_INIT
#define Z2_ENABLE_INIT ((void)0)
#undef Z2_ENABLE_WRITE
#define Z2_ENABLE_WRITE(STATE) (if(STATE) stepperZ2.Step_Clock(stepperZ2.getStatus() & STATUS_HIZ); else stepperZ2.softFree();)
#undef Z2_ENABLE_READ
#define Z2_ENABLE_READ (stepperZ2.getStatus() & STATUS_HIZ)
#undef Z2_DIR_INIT
#define Z2_DIR_INIT ((void)0)
#undef Z2_DIR_WRITE
#define Z2_DIR_WRITE(STATE) stepperZ2.Step_Clock(STATE)
#undef Y2_DIR_READ
#define Y2_DIR_READ (stepperZ2.getStatus() & STATUS_DIR)
#endif
#ifdef E0_IS_L6470
extern L6470 stepperE0;
#undef E0_ENABLE_INIT
#define E0_ENABLE_INIT ((void)0)
#undef E0_ENABLE_WRITE
#define E0_ENABLE_WRITE(STATE) (if(STATE) stepperE0.Step_Clock(stepperE0.getStatus() & STATUS_HIZ); else stepperE0.softFree();)
#undef E0_ENABLE_READ
#define E0_ENABLE_READ (stepperE0.getStatus() & STATUS_HIZ)
#undef E0_DIR_INIT
#define E0_DIR_INIT ((void)0)
#undef E0_DIR_WRITE
#define E0_DIR_WRITE(STATE) stepperE0.Step_Clock(STATE)
#undef E0_DIR_READ
#define E0_DIR_READ (stepperE0.getStatus() & STATUS_DIR)
#endif
#ifdef E1_IS_L6470
extern L6470 stepperE1;
#undef E1_ENABLE_INIT
#define E1_ENABLE_INIT ((void)0)
#undef E1_ENABLE_WRITE
#define E1_ENABLE_WRITE(STATE) (if(STATE) stepperE1.Step_Clock(stepperE1.getStatus() & STATUS_HIZ); else stepperE1.softFree();)
#undef E1_ENABLE_READ
#define E1_ENABLE_READ (stepperE1.getStatus() & STATUS_HIZ)
#undef E1_DIR_INIT
#define E1_DIR_INIT ((void)0)
#undef E1_DIR_WRITE
#define E1_DIR_WRITE(STATE) stepperE1.Step_Clock(STATE)
#undef E1_DIR_READ
#define E1_DIR_READ (stepperE1.getStatus() & STATUS_DIR)
#endif
#ifdef E2_IS_L6470
extern L6470 stepperE2;
#undef E2_ENABLE_INIT
#define E2_ENABLE_INIT ((void)0)
#undef E2_ENABLE_WRITE
#define E2_ENABLE_WRITE(STATE) (if(STATE) stepperE2.Step_Clock(stepperE2.getStatus() & STATUS_HIZ); else stepperE2.softFree();)
#undef E2_ENABLE_READ
#define E2_ENABLE_READ (stepperE2.getStatus() & STATUS_HIZ)
#undef E2_DIR_INIT
#define E2_DIR_INIT ((void)0)
#undef E2_DIR_WRITE
#define E2_DIR_WRITE(STATE) stepperE2.Step_Clock(STATE)
#undef E2_DIR_READ
#define E2_DIR_READ (stepperE2.getStatus() & STATUS_DIR)
#endif
#ifdef E3_IS_L6470
extern L6470 stepperE3;
#undef E3_ENABLE_INIT
#define E3_ENABLE_INIT ((void)0)
#undef E3_ENABLE_WRITE
#define E3_ENABLE_WRITE(STATE) (if(STATE) stepperE3.Step_Clock(stepperE3.getStatus() & STATUS_HIZ); else stepperE3.softFree();)
#undef E3_ENABLE_READ
#define E3_ENABLE_READ (stepperE3.getStatus() & STATUS_HIZ)
#undef E3_DIR_INIT
#define E3_DIR_INIT ((void)0)
#undef E3_DIR_WRITE
#define E3_DIR_WRITE(STATE) stepperE3.Step_Clock(STATE)
#undef E3_DIR_READ
#define E3_DIR_READ (stepperE3.getStatus() & STATUS_DIR)
#endif
#endif //HAVE_L6470DRIVER
#endif // STEPPER_INDIRECTION_H

View file

@ -296,8 +296,8 @@ void PID_autotune(float temp, int extruder, int ncycles)
SERIAL_PROTOCOLPGM(MSG_BIAS); SERIAL_PROTOCOL(bias);
SERIAL_PROTOCOLPGM(MSG_D); SERIAL_PROTOCOL(d);
SERIAL_PROTOCOLPGM(MSG_MIN); SERIAL_PROTOCOL(min);
SERIAL_PROTOCOLPGM(MSG_MAX); SERIAL_PROTOCOLLN(max);
SERIAL_PROTOCOLPGM(MSG_T_MIN); SERIAL_PROTOCOL(min);
SERIAL_PROTOCOLPGM(MSG_T_MAX); SERIAL_PROTOCOLLN(max);
if (cycles > 2) {
Ku = (4.0 * d) / (3.14159265 * (max - min) / 2.0);
Tu = ((float)(t_low + t_high) / 1000.0);

View file

@ -903,6 +903,7 @@ static void lcd_control_motion_menu() {
MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_Z, &max_acceleration_units_per_sq_second[Z_AXIS], 100, 99000, reset_acceleration_rates);
MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_E, &max_acceleration_units_per_sq_second[E_AXIS], 100, 99000, reset_acceleration_rates);
MENU_ITEM_EDIT(float5, MSG_A_RETRACT, &retract_acceleration, 100, 99000);
MENU_ITEM_EDIT(float5, MSG_A_TRAVEL, &travel_acceleration, 100, 99000);
MENU_ITEM_EDIT(float52, MSG_XSTEPS, &axis_steps_per_unit[X_AXIS], 5, 9999);
MENU_ITEM_EDIT(float52, MSG_YSTEPS, &axis_steps_per_unit[Y_AXIS], 5, 9999);
MENU_ITEM_EDIT(float51, MSG_ZSTEPS, &axis_steps_per_unit[Z_AXIS], 5, 9999);

View file

@ -84,7 +84,7 @@ void vector_3::debug(char* title)
SERIAL_PROTOCOL(y);
SERIAL_PROTOCOLPGM(" z: ");
SERIAL_PROTOCOL(z);
SERIAL_PROTOCOLPGM("\n");
SERIAL_EOL;
}
void apply_rotation_xyz(matrix_3x3 matrix, float &x, float& y, float& z)
@ -145,22 +145,17 @@ matrix_3x3 matrix_3x3::transpose(matrix_3x3 original)
return new_matrix;
}
void matrix_3x3::debug(char* title)
{
SERIAL_PROTOCOL(title);
SERIAL_PROTOCOL("\n");
int count = 0;
for(int i=0; i<3; i++)
{
for(int j=0; j<3; j++)
{
SERIAL_PROTOCOL(matrix[count]);
SERIAL_PROTOCOLPGM(" ");
count++;
}
SERIAL_PROTOCOLPGM("\n");
}
void matrix_3x3::debug(char* title) {
SERIAL_PROTOCOLLN(title);
int count = 0;
for(int i=0; i<3; i++) {
for(int j=0; j<3; j++) {
SERIAL_PROTOCOL(matrix[count] + 0.0001);
SERIAL_PROTOCOLPGM(" ");
count++;
}
SERIAL_EOL;
}
}
#endif // #ifdef ENABLE_AUTO_BED_LEVELING

View file

@ -27,11 +27,11 @@ We are actively looking for testers. So please try the current development versi
[![Coverity Scan Build Status](https://scan.coverity.com/projects/2224/badge.svg)](https://scan.coverity.com/projects/2224)
[![Travis Build Status](https://travis-ci.org/MarlinFirmware/Marlin.svg)](https://travis-ci.org/MarlinFirmware/Marlin)
What bugs are we working on: [Bug Fixing Round 2](https://github.com/MarlinFirmware/Marlin/milestones/Bug%20Fixing%20Round%202)
What bugs are we working on: [Bug Fixing Round 3](https://github.com/MarlinFirmware/Marlin/milestones/Bug%20Fixing%20Round%203)
## Contact
__IRC:__ #marlin-firmware @freenode ([WebChat Client](https://webchat.freenode.net/?channels=marlin-firmware), [Archive](http://energymonitor-dk.dns4e.net/marlin-firmware-log/))
__IRC:__ #marlin-firmware @freenode ([WebChat Client](https://webchat.freenode.net/?channels=marlin-firmware)
__Mailing List:__ marlin@lists.0l.de ([Subscribe](http://lists.0l.de/mailman/listinfo/marlin), [Archive](http://lists.0l.de/pipermail/marlin/))
@ -41,7 +41,7 @@ The current Marlin dev team consists of:
- Erik van der Zalm ([@ErikZalm](https://github.com/ErikZalm))
- [@daid](https://github.com/daid)
Sprinters lead developers are Kliment and caru.
Grbls lead developer is Simen Svale Skogsrud.
Sonney Jeon (Chamnit) improved some parts of grbl
@ -52,9 +52,9 @@ More features have been added by:
- Bradley Feldman,
- and others...
## Licence
## License
Marlin is published unde the [GPL license](/Documentation/COPYING.md) because I believe in open development.
Marlin is published under the [GPL license](/Documentation/COPYING.md) because I believe in open development.
Please do not use this code in products (3D printers, CNC etc) that are closed source or are crippled by a patent.
[![Flattr this git repo](http://api.flattr.com/button/flattr-badge-large.png)](https://flattr.com/submit/auto?user_id=ErikZalm&url=https://github.com/MarlinFirmware/Marlin&title=Marlin&language=&tags=github&category=software)