Merge branch 'Development' into delta_auto_bed_level
Conflicts: Marlin/Marlin_main.cpp
|
@ -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/
|
||||
|
|
723
ArduinoAddons/Arduino_1.x.x/libraries/L6470/L6470.cpp
Normal 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;
|
||||
}
|
286
ArduinoAddons/Arduino_1.x.x/libraries/L6470/L6470.h
Normal 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
|
53
ArduinoAddons/Arduino_1.x.x/libraries/L6470/keywords.txt
Normal 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)
|
||||
#######################################
|
17
ArduinoAddons/Arduino_1.x.x/libraries/TMC26XStepper/.gitignore
vendored
Normal 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
|
1813
ArduinoAddons/Arduino_1.x.x/libraries/TMC26XStepper/Doxyfile
Normal file
10
ArduinoAddons/Arduino_1.x.x/libraries/TMC26XStepper/LICENSE
Normal 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.
|
|
@ -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 world’s 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:
|
|
@ -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;
|
||||
}
|
|
@ -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, 1…15: 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,1…12: 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 0…255
|
||||
*
|
||||
* 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
|
||||
|
|
@ -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 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 List</span></a></li>
|
||||
<li><a href="globals.html"><span>File 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 <WProgram.h></code><br/>
|
||||
<code>#include <SPI.h></code><br/>
|
||||
<code>#include "<a class="el" href="_t_m_c26_x_stepper_8h_source.html">TMC26XStepper.h</a>"</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 </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a6560b3471273e99e280ba795e3469ede">DEFAULT_MICROSTEPPING_VALUE</a>   32</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a108f18bf4a30a0e0f0991ac0e4ce0579">DRIVER_CONTROL_REGISTER</a>   0x0ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a70a540d1090b989b8600b5e4776659fe">CHOPPER_CONFIG_REGISTER</a>   0x80000ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab9828bfaa075a0a8647c709136016317">COOL_STEP_REGISTER</a>   0xA0000ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a478d9bde09a6528eef6af6ffeeb6caba">STALL_GUARD2_LOAD_MEASURE_REGISTER</a>   0xC0000ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#af35f569d42ea3b1d634901a3b6a908ee">DRIVER_CONFIG_REGISTER</a>   0xE0000ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a3b02ee1f518b0c90c16488f937abd443">REGISTER_BIT_PATTERN</a>   0xFFFFFul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8f5cb0c066109ffb18cefc0e85ee1d1b">MICROSTEPPING_PATTERN</a>   0xFul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa64245f223209654c60588e4558e0bab">STEP_INTERPOLATION</a>   0x200ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a770601bf0153e4bc639b9c3005b15af7">DOUBLE_EDGE_STEP</a>   0x100ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a4fb1c008e2ff76eee9362600eed112e1">VSENSE</a>   0x40ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a143b7757272f07866d9655bde8303d9a">READ_MICROSTEP_POSTION</a>   0x0ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac1bd4da94fab7ce1049be2f866211819">READ_STALL_GUARD_READING</a>   0x10ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </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>   0x20ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a88a4b45fa6385eba8aa4f0342334b832">READ_SELECTION_PATTERN</a>   0x30ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a57418a67ff726d540b813230bca1d536">CHOPPER_MODE_STANDARD</a>   0x0ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </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>   0x4000ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa4e49237f2671e7f28aa34ae0e89da8d">T_OFF_PATTERN</a>   0xful</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a64520580cffd416668f3b91bd60f84e1">RANDOM_TOFF_TIME</a>   0x2000ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a42cb2ce84258587d514ec3268548ba89">BLANK_TIMING_PATTERN</a>   0x18000ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#abdac78f7f2c506972265a8e5883e1eae">BLANK_TIMING_SHIFT</a>   15</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a424c248097b38c1e29e6a58ad48e6bd9">HYSTERESIS_DECREMENT_PATTERN</a>   0x1800ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a36e554a87785ce6ba998b79aae9e74e0">HYSTERESIS_DECREMENT_SHIFT</a>   11</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ad9d2302f6d61cd84a612a2e2bcdeb56e">HYSTERESIS_LOW_VALUE_PATTERN</a>   0x780ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a38ce0bb0fa20db28351ac9167f28db98">HYSTERESIS_LOW_SHIFT</a>   7</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a0de4e98b412dced62c3a4452b7483af3">HYSTERESIS_START_VALUE_PATTERN</a>   0x78ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac2c1c939256126e605396c4aaee3c804">HYSTERESIS_START_VALUE_SHIFT</a>   4</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a7659d842c803e47ba911a2a6e26327f3">T_OFF_TIMING_PATERN</a>   0xFul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8a261a77d198b85f6dd8416387b354b3">MINIMUM_CURRENT_FOURTH</a>   0x8000ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#adbe13a0464355e42fbe786ca5f58ed8d">CURRENT_DOWN_STEP_SPEED_PATTERN</a>   0x6000ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ac8f748bf735c447dbed7dd4c7b631a87">SE_MAX_PATTERN</a>   0xF00ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#aba6c07e5672e34e618bb3a550ab0d2bc">SE_CURRENT_STEP_WIDTH_PATTERN</a>   0x60ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae1862dfb958c03698b0abd95fda033ea">SE_MIN_PATTERN</a>   0xful</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#afdbbefabd0c29c4b6e403c4663d0f0be">STALL_GUARD_FILTER_ENABLED</a>   0x10000ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae631457932894a974334892704550ecc">STALL_GUARD_TRESHHOLD_VALUE_PATTERN</a>   0x17F00ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a99dcb8c6d98b0b54c23699a3f90450e4">CURRENT_SCALING_PATTERN</a>   0x1Ful</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a99ac04f0615556fc13c0c9f3e1c1b49d">STALL_GUARD_CONFIG_PATTERN</a>   0x17F00ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a6a1cb1fd61cf7c570f94376fa11fe55b">STALL_GUARD_VALUE_PATTERN</a>   0x7F00ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa09ef662fd19bf2d063d6bd0f48eca14">STATUS_STALL_GUARD_STATUS</a>   0x1ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#adbb23d2f055c9eab55eac29d1a75deb4">STATUS_OVER_TEMPERATURE_SHUTDOWN</a>   0x2ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#aa317fd77f2f26fdfbfd331e21d9069e8">STATUS_OVER_TEMPERATURE_WARNING</a>   0x4ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a8e03041302a092174fa33b3cf837dca2">STATUS_SHORT_TO_GROUND_A</a>   0x8ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a903c3eba99695a32c6736463dcfd93ae">STATUS_SHORT_TO_GROUND_B</a>   0x10ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ae9cbbe5af7188e6bff8fe412f8e42f59">STATUS_OPEN_LOAD_A</a>   0x20ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab29dc5cd6c6c4e5bf99e71bd563e1be1">STATUS_OPEN_LOAD_B</a>   0x40ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#ab96ed1635faee6650e9cce73598a2773">STATUS_STAND_STILL</a>   0x80ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a5c3d76da63f585e37813c32be2e11ab7">READOUT_VALUE_PATTERN</a>   0xFFC00ul</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8cpp.html#a54a6d12e96d851361974b10614a00e45">INITIAL_MICROSTEPPING</a>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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>   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  <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>
|
|
@ -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 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 List</span></a></li>
|
||||
<li><a href="globals.html"><span>File Members</span></a></li>
|
||||
</ul>
|
||||
</div>
|
||||
</div>
|
||||
<div class="header">
|
||||
<div class="summary">
|
||||
<a href="#nested-classes">Classes</a> |
|
||||
<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  </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"> </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 </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#add42eee34f674f92c19bcd5266d2445f">TMC26X_OVERTEMPERATURE_PREWARING</a>   1</td></tr>
|
||||
<tr><td class="mdescLeft"> </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 </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#adae814ce848677abd87758c7ac79a436">TMC26X_OVERTEMPERATURE_SHUTDOWN</a>   2</td></tr>
|
||||
<tr><td class="mdescLeft"> </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 </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#aff05d4a47ef8821322ccc2a20785fbee">TMC26X_READOUT_POSITION</a>   0</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#ac864ff8886123039c7d2d3c617f7ef87">TMC26X_READOUT_STALLGUARD</a>   1</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#a01760ad15e3846536526a990efe47094">TMC26X_READOUT_CURRENT</a>   3</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#a28b1774bd4aa854fb5e4b6dc7db96ecb">COOL_STEP_HALF_CS_LIMIT</a>   0</td></tr>
|
||||
<tr><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="_t_m_c26_x_stepper_8h.html#a1a4db5eafd0a9247677153cb4c8b7d54">COOL_STEP_QUARTDER_CS_LIMIT</a>   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>   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>   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>   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>   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>   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>   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>   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  <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>
|
|
@ -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 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 List</span></a></li>
|
||||
<li><a href="globals.html"><span>File 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 "Software"), 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 "AS IS", 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 & 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  <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>
|
|
@ -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 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 List</span></a></li>
|
||||
<li><a href="classes.html"><span>Class Index</span></a></li>
|
||||
<li><a href="functions.html"><span>Class 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  <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>
|
After Width: | Height: | Size: 677 B |
|
@ -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 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 List</span></a></li>
|
||||
<li><a href="classes.html"><span>Class Index</span></a></li>
|
||||
<li><a href="functions.html"><span>Class 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  <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>
|
|
@ -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 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 List</span></a></li>
|
||||
<li class="current"><a href="classes.html"><span>Class Index</span></a></li>
|
||||
<li><a href="functions.html"><span>Class 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">  T  </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>   </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  <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>
|
After Width: | Height: | Size: 126 B |
|
@ -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+ */
|
||||
}
|
||||
}
|
||||
|
After Width: | Height: | Size: 3.8 KiB |
|
@ -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 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 List</span></a></li>
|
||||
<li><a href="globals.html"><span>File 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  <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>
|
|
@ -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 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 List</span></a></li>
|
||||
<li><a href="classes.html"><span>Class Index</span></a></li>
|
||||
<li class="current"><a href="functions.html"><span>Class 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  <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>
|
|
@ -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 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 List</span></a></li>
|
||||
<li><a href="classes.html"><span>Class Index</span></a></li>
|
||||
<li class="current"><a href="functions.html"><span>Class 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">
|
||||
 
|
||||
|
||||
<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  <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>
|
|
@ -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 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 List</span></a></li>
|
||||
<li class="current"><a href="globals.html"><span>File 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  <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>
|
|
@ -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 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 List</span></a></li>
|
||||
<li class="current"><a href="globals.html"><span>File 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">
|
||||
 
|
||||
|
||||
<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  <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>
|
|
@ -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 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  <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>
|
64
ArduinoAddons/Arduino_1.x.x/libraries/TMC26XStepper/documentation/html/jquery.js
vendored
Normal 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 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 List</span></a></li>
|
||||
<li><a href="globals.html"><span>File 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  <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>
|
After Width: | Height: | Size: 159 B |
After Width: | Height: | Size: 97 B |
After Width: | Height: | Size: 118 B |
After Width: | Height: | Size: 140 B |
After Width: | Height: | Size: 178 B |
After Width: | Height: | Size: 192 B |
After Width: | Height: | Size: 189 B |
|
@ -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);
|
||||
}
|
|
@ -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();
|
||||
}
|
||||
|
||||
|
|
@ -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++;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
|
@ -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;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
|
@ -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();
|
||||
}
|
||||
|
||||
|
||||
|
|
@ -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);
|
||||
}
|
||||
}
|
||||
|
|
@ -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);
|
||||
}
|
||||
}
|
||||
|
|
@ -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);
|
||||
}
|
||||
|
|
@ -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);
|
||||
}
|
||||
}
|
|
@ -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);
|
||||
}
|
||||
}
|
||||
|
|
@ -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());
|
||||
}
|
||||
}
|
After Width: | Height: | Size: 8.6 KiB |
After Width: | Height: | Size: 7.9 KiB |
After Width: | Height: | Size: 32 KiB |
|
@ -0,0 +1,2 @@
|
|||
mode.id=processing.mode.java.JavaMode
|
||||
mode=Java
|
|
@ -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
|
|
@ -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.
|
||||
*
|
||||
*/
|
1
Documentation/changelog.md
Normal file
|
@ -0,0 +1 @@
|
|||
|
|
@ -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
|
||||
|
@ -301,35 +301,21 @@ your extruder heater takes 2 minutes to hit the target on heating.
|
|||
// 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
|
||||
|
||||
#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
|
||||
|
||||
#ifdef ENDSTOPPULLUPS
|
||||
// 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
|
||||
#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
|
||||
|
||||
|
@ -346,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
|
||||
|
@ -364,17 +351,26 @@ 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_MIN_POS 0
|
||||
#define Y_MAX_POS 205
|
||||
#define Y_MIN_POS 0
|
||||
#define Z_MAX_POS 200
|
||||
#define Z_MIN_POS 0
|
||||
#define X_MAX_POS 200
|
||||
#define Y_MAX_POS 200
|
||||
#define Z_MAX_POS 200
|
||||
|
||||
#define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)
|
||||
#define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
|
||||
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
|
||||
|
||||
//===========================================================================
|
||||
//============================= Filament Runout Sensor ======================
|
||||
//===========================================================================
|
||||
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
|
||||
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
|
||||
// It is assumed that when logic high = filament available
|
||||
// when logic low = filament ran out
|
||||
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
|
||||
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
|
||||
|
||||
//===========================================================================
|
||||
//============================= Bed Auto Leveling ===========================
|
||||
|
@ -402,12 +398,19 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||
|
||||
#ifdef AUTO_BED_LEVELING_GRID
|
||||
|
||||
// Use one of these defines to specify the origin
|
||||
// for a topographical map to be printed for your bed.
|
||||
enum { OriginBackLeft, OriginFrontLeft, OriginBackRight, OriginFrontRight };
|
||||
#define TOPO_ORIGIN OriginFrontLeft
|
||||
|
||||
// The edges of the rectangle in which to probe
|
||||
#define LEFT_PROBE_BED_POSITION 15
|
||||
#define RIGHT_PROBE_BED_POSITION 170
|
||||
#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
|
||||
// You probably don't need more than 3 (squared=9)
|
||||
#define AUTO_BED_LEVELING_GRID_POINTS 2
|
||||
|
@ -429,8 +432,8 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||
|
||||
// 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.
|
||||
|
@ -442,6 +445,9 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||
#define Z_RAISE_BETWEEN_PROBINGS 5 //How much the extruder will be raised when traveling from between next probing points
|
||||
#define Z_RAISE_AFTER_PROBING 15 //How much the extruder will be raised after the last probing point.
|
||||
|
||||
// #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.
|
||||
|
||||
|
@ -478,10 +484,12 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||
|
||||
// Manual homing switch locations:
|
||||
// For deltabots this means top and center of the Cartesian print volume.
|
||||
#ifdef MANUAL_HOME_POSITIONS
|
||||
#define MANUAL_X_HOME_POS 0
|
||||
#define MANUAL_Y_HOME_POS 0
|
||||
#define MANUAL_Z_HOME_POS 0
|
||||
//#define MANUAL_Z_HOME_POS 402 // For delta: Distance between nozzle and print surface after homing.
|
||||
#endif
|
||||
|
||||
//// MOVEMENT SETTINGS
|
||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||
|
@ -489,12 +497,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).
|
||||
|
@ -535,11 +544,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=============================
|
||||
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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}
|
||||
|
@ -285,8 +286,8 @@
|
|||
//===========================================================================
|
||||
|
||||
#define ENCODER_RATE_MULTIPLIER // If defined, certain menu edit operations automatically multiply the steps when the encoder is moved quickly
|
||||
#define ENCODER_10X_STEPS_PER_SEC 75 // If the encoder steps per sec exceed this value, multiple the steps moved by ten to quickly advance the value
|
||||
#define ENCODER_100X_STEPS_PER_SEC 160 // If the encoder steps per sec exceed this value, multiple the steps moved by 100 to really quickly advance the value
|
||||
#define ENCODER_10X_STEPS_PER_SEC 75 // If the encoder steps per sec exceeds this value, multiply steps moved x10 to quickly advance the value
|
||||
#define ENCODER_100X_STEPS_PER_SEC 160 // If the encoder steps per sec exceeds this value, multiply steps moved x100 to really quickly advance the value
|
||||
//#define ENCODER_RATE_MULTIPLIER_DEBUG // If defined, output the encoder steps per second value
|
||||
|
||||
//#define CHDK 4 //Pin for triggering CHDK to take a picture see how to use it here http://captain-slow.dk/2014/03/09/3d-printing-timelapses/
|
||||
|
@ -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 ============================
|
||||
//===========================================================================
|
||||
|
|
|
@ -32,6 +32,9 @@
|
|||
#include "WProgram.h"
|
||||
#endif
|
||||
|
||||
#define BIT(b) (1<<(b))
|
||||
#define TEST(n,b) (((n)&BIT(b))!=0)
|
||||
|
||||
// Arduino < 1.0.0 does not define this, so we need to do it ourselves
|
||||
#ifndef analogInputToDigitalPin
|
||||
#define analogInputToDigitalPin(p) ((p) + 0xA0)
|
||||
|
@ -112,11 +115,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 +127,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 +140,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 +152,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 */
|
||||
|
@ -205,6 +208,10 @@ void prepare_move();
|
|||
void kill();
|
||||
void Stop();
|
||||
|
||||
#ifdef FILAMENT_RUNOUT_SENSOR
|
||||
void filrunout();
|
||||
#endif
|
||||
|
||||
bool IsStopped();
|
||||
|
||||
bool enquecommand(const char *cmd); //put a single ASCII command at the end of the current buffer or return false when it is full
|
||||
|
|
|
@ -47,10 +47,20 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
||||
#if HAS_DIGIPOTSS
|
||||
#include <SPI.h>
|
||||
#endif
|
||||
|
||||
#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
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
||||
#if HAS_DIGIPOTSS
|
||||
#include <SPI.h>
|
||||
#endif
|
||||
|
||||
|
|
|
@ -76,7 +76,7 @@ void MarlinSerial::begin(long baud) {
|
|||
#endif
|
||||
|
||||
if (useU2X) {
|
||||
M_UCSRxA = 1 << M_U2Xx;
|
||||
M_UCSRxA = BIT(M_U2Xx);
|
||||
baud_setting = (F_CPU / 4 / baud - 1) / 2;
|
||||
} else {
|
||||
M_UCSRxA = 0;
|
||||
|
|
|
@ -97,14 +97,14 @@ class MarlinSerial { //: public Stream
|
|||
}
|
||||
|
||||
FORCE_INLINE void write(uint8_t c) {
|
||||
while (!((M_UCSRxA) & (1 << M_UDREx)))
|
||||
while (!TEST(M_UCSRxA, M_UDREx))
|
||||
;
|
||||
|
||||
M_UDRx = c;
|
||||
}
|
||||
|
||||
FORCE_INLINE void checkRx(void) {
|
||||
if ((M_UCSRxA & (1<<M_RXCx)) != 0) {
|
||||
if (TEST(M_UCSRxA, M_RXCx)) {
|
||||
unsigned char c = M_UDRx;
|
||||
int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;
|
||||
|
||||
|
|
|
@ -62,7 +62,7 @@
|
|||
#include "Servo.h"
|
||||
#endif
|
||||
|
||||
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
||||
#if HAS_DIGIPOTSS
|
||||
#include <SPI.h>
|
||||
#endif
|
||||
|
||||
|
@ -201,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;
|
||||
|
@ -369,6 +373,10 @@ bool cancel_heatup = false;
|
|||
int meas_delay_cm = MEASUREMENT_DELAY_CM; //distance delay setting
|
||||
#endif
|
||||
|
||||
#ifdef FILAMENT_RUNOUT_SENSOR
|
||||
static bool filrunoutEnqued = false;
|
||||
#endif
|
||||
|
||||
const char errormagic[] PROGMEM = "Error:";
|
||||
const char echomagic[] PROGMEM = "echo:";
|
||||
|
||||
|
@ -528,6 +536,16 @@ void setup_killpin()
|
|||
#endif
|
||||
}
|
||||
|
||||
void setup_filrunoutpin()
|
||||
{
|
||||
#if defined(FILRUNOUT_PIN) && FILRUNOUT_PIN > -1
|
||||
pinMode(FILRUNOUT_PIN,INPUT);
|
||||
#if defined(ENDSTOPPULLUP_FIL_RUNOUT)
|
||||
WRITE(FILLRUNOUT_PIN,HIGH);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
// Set home pin
|
||||
void setup_homepin(void)
|
||||
{
|
||||
|
@ -604,6 +622,7 @@ void servo_init()
|
|||
void setup()
|
||||
{
|
||||
setup_killpin();
|
||||
setup_filrunoutpin();
|
||||
setup_powerhold();
|
||||
MYSERIAL.begin(BAUDRATE);
|
||||
SERIAL_PROTOCOLLNPGM("start");
|
||||
|
@ -768,7 +787,7 @@ void get_command()
|
|||
while(cmdbuffer[bufindw][count] != '*') checksum = checksum^cmdbuffer[bufindw][count++];
|
||||
strchr_pointer = strchr(cmdbuffer[bufindw], '*');
|
||||
|
||||
if( (int)(strtod(strchr_pointer + 1, NULL)) != checksum) {
|
||||
if(strtol(strchr_pointer + 1, NULL, 10) != checksum) {
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORPGM(MSG_ERR_CHECKSUM_MISMATCH);
|
||||
SERIAL_ERRORLN(gcode_LastN);
|
||||
|
@ -804,7 +823,7 @@ void get_command()
|
|||
}
|
||||
if((strchr(cmdbuffer[bufindw], 'G') != NULL)){
|
||||
strchr_pointer = strchr(cmdbuffer[bufindw], 'G');
|
||||
switch((int)((strtod(strchr_pointer + 1, NULL)))){
|
||||
switch(strtol(strchr_pointer + 1, NULL, 10)){
|
||||
case 0:
|
||||
case 1:
|
||||
case 2:
|
||||
|
@ -1158,7 +1177,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();
|
||||
|
@ -1191,7 +1221,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;
|
||||
|
@ -1467,11 +1497,17 @@ static void homeaxis(int axis) {
|
|||
st_synchronize();
|
||||
|
||||
destination[axis] = 2*home_retract_mm(axis) * axis_home_dir;
|
||||
#ifdef DELTA
|
||||
|
||||
if (homing_bump_divisor[axis] >= 1)
|
||||
{
|
||||
feedrate = homing_feedrate[axis]/homing_bump_divisor[axis];
|
||||
}
|
||||
else
|
||||
{
|
||||
feedrate = homing_feedrate[axis]/10;
|
||||
#else
|
||||
feedrate = homing_feedrate[axis]/2 ;
|
||||
#endif
|
||||
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
|
||||
|
@ -1934,41 +1970,32 @@ inline void gcode_G28() {
|
|||
|
||||
#ifdef AUTO_BED_LEVELING_GRID
|
||||
|
||||
#define MIN_PROBE_EDGE 20 // The probe square sides can be no smaller than this
|
||||
|
||||
// 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.
|
||||
#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.
|
||||
#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.
|
||||
#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.
|
||||
|
||||
// Check if Probe_Offset * Grid Points is greater than Probing Range
|
||||
|
||||
#elif abs(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"
|
||||
#elif abs(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"
|
||||
#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.
|
||||
#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.
|
||||
#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.
|
||||
#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.
|
||||
#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.
|
||||
#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.
|
||||
#error "The given ABL_PROBE_PT_3_Y can't be reached by the probe."
|
||||
#endif
|
||||
|
||||
#endif // !AUTO_BED_LEVELING_GRID
|
||||
|
@ -1985,6 +2012,8 @@ inline void gcode_G28() {
|
|||
* Not supported by non-linear delta printer bed leveling.
|
||||
* 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.
|
||||
|
@ -2005,12 +2034,6 @@ inline void gcode_G28() {
|
|||
* Usage: "G29 E" or "G29 e"
|
||||
*
|
||||
*/
|
||||
|
||||
// Use one of these defines to specify the origin
|
||||
// for a topographical map to be printed for your bed.
|
||||
enum { OriginBackLeft, OriginFrontLeft, OriginBackRight, OriginFrontRight };
|
||||
#define TOPO_ORIGIN OriginFrontLeft
|
||||
|
||||
inline void gcode_G29() {
|
||||
|
||||
// Prevent user from running a G29 without first homing in X and Y
|
||||
|
@ -2046,12 +2069,14 @@ inline void gcode_G28() {
|
|||
int auto_bed_leveling_grid_points = AUTO_BED_LEVELING_GRID_POINTS;
|
||||
#ifndef DELTA
|
||||
if (code_seen('P')) auto_bed_leveling_grid_points = code_value_long();
|
||||
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;
|
||||
}
|
||||
#endif
|
||||
|
||||
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,
|
||||
|
@ -2228,14 +2253,15 @@ inline void gcode_G28() {
|
|||
|
||||
if (verbose_level) {
|
||||
SERIAL_PROTOCOLPGM("Eqn coefficients: a: ");
|
||||
SERIAL_PROTOCOL(plane_equation_coefficients[0] + 0.0001);
|
||||
SERIAL_PROTOCOL_F(plane_equation_coefficients[0], 8);
|
||||
SERIAL_PROTOCOLPGM(" b: ");
|
||||
SERIAL_PROTOCOL(plane_equation_coefficients[1] + 0.0001);
|
||||
SERIAL_PROTOCOL_F(plane_equation_coefficients[1], 8);
|
||||
SERIAL_PROTOCOLPGM(" d: ");
|
||||
SERIAL_PROTOCOLLN(plane_equation_coefficients[2] + 0.0001);
|
||||
SERIAL_PROTOCOL_F(plane_equation_coefficients[2], 8);
|
||||
SERIAL_EOL;
|
||||
if (verbose_level > 2) {
|
||||
SERIAL_PROTOCOLPGM("Mean of sampled points: ");
|
||||
SERIAL_PROTOCOL_F(mean, 6);
|
||||
SERIAL_PROTOCOL_F(mean, 8);
|
||||
SERIAL_EOL;
|
||||
}
|
||||
}
|
||||
|
@ -2246,15 +2272,20 @@ inline void gcode_G28() {
|
|||
|
||||
SERIAL_PROTOCOLPGM(" \nBed Height Topography: \n");
|
||||
#if TOPO_ORIGIN == OriginFrontLeft
|
||||
SERIAL_PROTOCOLPGM("+-----------+\n");
|
||||
SERIAL_PROTOCOLPGM("|...Back....|\n");
|
||||
SERIAL_PROTOCOLPGM("|Left..Right|\n");
|
||||
SERIAL_PROTOCOLPGM("|...Front...|\n");
|
||||
SERIAL_PROTOCOLPGM("+-----------+\n");
|
||||
for (yy = auto_bed_leveling_grid_points - 1; yy >= 0; yy--)
|
||||
#else
|
||||
for (yy = 0; yy < auto_bed_leveling_grid_points; yy++)
|
||||
#endif
|
||||
{
|
||||
#if TOPO_ORIGIN == OriginBackRight
|
||||
for (xx = auto_bed_leveling_grid_points - 1; xx >= 0; xx--)
|
||||
#else
|
||||
for (xx = 0; xx < auto_bed_leveling_grid_points; xx++)
|
||||
#else
|
||||
for (xx = auto_bed_leveling_grid_points - 1; xx >= 0; xx--)
|
||||
#endif
|
||||
{
|
||||
int ind =
|
||||
|
@ -2333,6 +2364,11 @@ inline void gcode_G28() {
|
|||
#elif not defined(SERVO_ENDSTOPS)
|
||||
retract_z_probe();
|
||||
#endif
|
||||
|
||||
#ifdef Z_PROBE_END_SCRIPT
|
||||
enquecommands_P(PSTR(Z_PROBE_END_SCRIPT));
|
||||
st_synchronize();
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifndef Z_PROBE_SLED
|
||||
|
@ -3480,16 +3516,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;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -4099,11 +4153,11 @@ inline void gcode_M400() { st_synchronize(); }
|
|||
#ifdef FILAMENT_SENSOR
|
||||
|
||||
/**
|
||||
* M404: Display or set the nominal filament width (3mm, 1.75mm ) N<3.0>
|
||||
* M404: Display or set the nominal filament width (3mm, 1.75mm ) W<3.0>
|
||||
*/
|
||||
inline void gcode_M404() {
|
||||
#if FILWIDTH_PIN > -1
|
||||
if (code_seen('N')) {
|
||||
if (code_seen('W')) {
|
||||
filament_width_nominal = code_value();
|
||||
}
|
||||
else {
|
||||
|
@ -4329,6 +4383,11 @@ inline void gcode_M503() {
|
|||
plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], target[E_AXIS], fr60, active_extruder); //move z back
|
||||
plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], lastpos[E_AXIS], fr60, active_extruder); //final untretract
|
||||
#endif
|
||||
|
||||
#ifdef FILAMENT_RUNOUT_SENSOR
|
||||
filrunoutEnqued = false;
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
#endif // FILAMENTCHANGEENABLE
|
||||
|
@ -4383,7 +4442,7 @@ inline void gcode_M503() {
|
|||
* M907: Set digital trimpot motor current using axis codes X, Y, Z, E, B, S
|
||||
*/
|
||||
inline void gcode_M907() {
|
||||
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
||||
#if HAS_DIGIPOTSS
|
||||
for (int i=0;i<NUM_AXIS;i++)
|
||||
if (code_seen(axis_codes[i])) digipot_current(i, code_value());
|
||||
if (code_seen('B')) digipot_current(4, code_value());
|
||||
|
@ -4406,7 +4465,7 @@ inline void gcode_M907() {
|
|||
#endif
|
||||
}
|
||||
|
||||
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
||||
#if HAS_DIGIPOTSS
|
||||
|
||||
/**
|
||||
* M908: Control digital trimpot directly (M908 P<pin> S<current>)
|
||||
|
@ -4418,7 +4477,7 @@ inline void gcode_M907() {
|
|||
);
|
||||
}
|
||||
|
||||
#endif // DIGIPOTSS_PIN
|
||||
#endif // HAS_DIGIPOTSS
|
||||
|
||||
// M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
|
||||
inline void gcode_M350() {
|
||||
|
@ -4436,7 +4495,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);
|
||||
|
@ -4635,7 +4694,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
|
||||
|
@ -5005,11 +5064,11 @@ void process_commands() {
|
|||
gcode_M907();
|
||||
break;
|
||||
|
||||
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
||||
#if HAS_DIGIPOTSS
|
||||
case 908: // M908 Control digital trimpot directly.
|
||||
gcode_M908();
|
||||
break;
|
||||
#endif // DIGIPOTSS_PIN
|
||||
#endif // HAS_DIGIPOTSS
|
||||
|
||||
case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
|
||||
gcode_M350();
|
||||
|
@ -5367,41 +5426,34 @@ void prepare_arc_move(char isclockwise) {
|
|||
#endif
|
||||
#endif
|
||||
|
||||
unsigned long lastMotor = 0; //Save the time for when a motor was turned on last
|
||||
unsigned long lastMotorCheck = 0;
|
||||
unsigned long lastMotor = 0; // Last time a motor was turned on
|
||||
unsigned long lastMotorCheck = 0; // Last time the state was checked
|
||||
|
||||
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 EXTRUDERS > 2
|
||||
|| (READ(E2_ENABLE_PIN) == (E_ENABLE_ON))
|
||||
#endif
|
||||
#if EXTRUDER > 1
|
||||
void controllerFan() {
|
||||
uint32_t ms = millis();
|
||||
if (ms >= lastMotorCheck + 2500) { // Not a time critical function, so we only check every 2500ms
|
||||
lastMotorCheck = ms;
|
||||
if (X_ENABLE_READ == X_ENABLE_ON || Y_ENABLE_READ == Y_ENABLE_ON || Z_ENABLE_READ == Z_ENABLE_ON || soft_pwm_bed > 0
|
||||
|| E0_ENABLE_READ == E_ENABLE_ON // If any of the drivers are enabled...
|
||||
#if EXTRUDERS > 1
|
||||
|| E1_ENABLE_READ == E_ENABLE_ON
|
||||
#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))
|
||||
#if EXTRUDERS > 2
|
||||
|| E2_ENABLE_READ == E_ENABLE_ON
|
||||
#if EXTRUDERS > 3
|
||||
|| E3_ENABLE_READ == E_ENABLE_ON
|
||||
#endif
|
||||
|| (READ(E0_ENABLE_PIN) == (E_ENABLE_ON))) //If any of the drivers are enabled...
|
||||
{
|
||||
lastMotor = millis(); //... set time to NOW so the fan will turn on
|
||||
#endif
|
||||
#endif
|
||||
) {
|
||||
lastMotor = ms; //... set time to NOW so the fan will turn on
|
||||
}
|
||||
|
||||
if ((millis() - lastMotor) >= (CONTROLLERFAN_SECS*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC...
|
||||
{
|
||||
digitalWrite(CONTROLLERFAN_PIN, 0);
|
||||
analogWrite(CONTROLLERFAN_PIN, 0);
|
||||
}
|
||||
else
|
||||
{
|
||||
uint8_t speed = (lastMotor == 0 || ms >= lastMotor + (CONTROLLERFAN_SECS * 1000UL)) ? 0 : CONTROLLERFAN_SPEED;
|
||||
// allows digital or PWM fan output to be used (see M42 handling)
|
||||
digitalWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
|
||||
analogWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
|
||||
}
|
||||
digitalWrite(CONTROLLERFAN_PIN, speed);
|
||||
analogWrite(CONTROLLERFAN_PIN, speed);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
@ -5525,6 +5577,12 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument s
|
|||
const int KILL_DELAY = 10000;
|
||||
#endif
|
||||
|
||||
#if defined(FILRUNOUT_PIN) && FILRUNOUT_PIN > -1
|
||||
if(card.sdprinting) {
|
||||
if(!(READ(FILRUNOUT_PIN))^FIL_RUNOUT_INVERTING)
|
||||
filrunout(); }
|
||||
#endif
|
||||
|
||||
#if defined(HOME_PIN) && HOME_PIN > -1
|
||||
static int homeDebounceCount = 0; // poor man's debouncing count
|
||||
const int HOME_DEBOUNCE_DELAY = 10000;
|
||||
|
@ -5611,7 +5669,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];
|
||||
|
@ -5623,7 +5681,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)
|
||||
|
@ -5673,6 +5731,16 @@ void kill()
|
|||
while(1) { /* Intentionally left empty */ } // Wait for reset
|
||||
}
|
||||
|
||||
#ifdef FILAMENT_RUNOUT_SENSOR
|
||||
void filrunout()
|
||||
{
|
||||
if filrunoutEnqued == false {
|
||||
filrunoutEnqued = true;
|
||||
enquecommand("M600");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void Stop()
|
||||
{
|
||||
disable_heater();
|
||||
|
|
|
@ -35,14 +35,14 @@
|
|||
*/
|
||||
static void spiInit(uint8_t spiRate) {
|
||||
// See avr processor documentation
|
||||
SPCR = (1 << SPE) | (1 << MSTR) | (spiRate >> 1);
|
||||
SPSR = spiRate & 1 || spiRate == 6 ? 0 : 1 << SPI2X;
|
||||
SPCR = BIT(SPE) | BIT(MSTR) | (spiRate >> 1);
|
||||
SPSR = spiRate & 1 || spiRate == 6 ? 0 : BIT(SPI2X);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI receive a byte */
|
||||
static uint8_t spiRec() {
|
||||
SPDR = 0XFF;
|
||||
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ }
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
return SPDR;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
|
@ -52,18 +52,18 @@ void spiRead(uint8_t* buf, uint16_t nbyte) {
|
|||
if (nbyte-- == 0) return;
|
||||
SPDR = 0XFF;
|
||||
for (uint16_t i = 0; i < nbyte; i++) {
|
||||
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ }
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
buf[i] = SPDR;
|
||||
SPDR = 0XFF;
|
||||
}
|
||||
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ }
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
buf[nbyte] = SPDR;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI send a byte */
|
||||
static void spiSend(uint8_t b) {
|
||||
SPDR = b;
|
||||
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ }
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI send block - only one call so force inline */
|
||||
|
@ -71,12 +71,12 @@ static inline __attribute__((always_inline))
|
|||
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
||||
SPDR = token;
|
||||
for (uint16_t i = 0; i < 512; i += 2) {
|
||||
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ }
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
SPDR = buf[i];
|
||||
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ }
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
SPDR = buf[i + 1];
|
||||
}
|
||||
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ }
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
#else // SOFTWARE_SPI
|
||||
|
|
|
@ -334,9 +334,9 @@ static inline __attribute__((always_inline))
|
|||
void setPinMode(uint8_t pin, uint8_t mode) {
|
||||
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
||||
if (mode) {
|
||||
*digitalPinMap[pin].ddr |= 1 << digitalPinMap[pin].bit;
|
||||
*digitalPinMap[pin].ddr |= BIT(digitalPinMap[pin].bit);
|
||||
} else {
|
||||
*digitalPinMap[pin].ddr &= ~(1 << digitalPinMap[pin].bit);
|
||||
*digitalPinMap[pin].ddr &= ~BIT(digitalPinMap[pin].bit);
|
||||
}
|
||||
} else {
|
||||
badPinNumber();
|
||||
|
@ -354,9 +354,9 @@ static inline __attribute__((always_inline))
|
|||
void fastDigitalWrite(uint8_t pin, uint8_t value) {
|
||||
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
||||
if (value) {
|
||||
*digitalPinMap[pin].port |= 1 << digitalPinMap[pin].bit;
|
||||
*digitalPinMap[pin].port |= BIT(digitalPinMap[pin].bit);
|
||||
} else {
|
||||
*digitalPinMap[pin].port &= ~(1 << digitalPinMap[pin].bit);
|
||||
*digitalPinMap[pin].port &= ~BIT(digitalPinMap[pin].bit);
|
||||
}
|
||||
} else {
|
||||
badPinNumber();
|
||||
|
|
|
@ -171,9 +171,9 @@ static inline uint8_t FAT_SECOND(uint16_t fatTime) {
|
|||
return 2*(fatTime & 0X1F);
|
||||
}
|
||||
/** Default date for file timestamps is 1 Jan 2000 */
|
||||
uint16_t const FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | (1 << 5) | 1;
|
||||
uint16_t const FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | BIT(5) | 1;
|
||||
/** Default time for file timestamp is 1 am */
|
||||
uint16_t const FAT_DEFAULT_TIME = (1 << 11);
|
||||
uint16_t const FAT_DEFAULT_TIME = BIT(11);
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \class SdBaseFile
|
||||
|
|
|
@ -360,7 +360,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
|
|||
blocksPerCluster_ = fbs->sectorsPerCluster;
|
||||
// determine shift that is same as multiply by blocksPerCluster_
|
||||
clusterSizeShift_ = 0;
|
||||
while (blocksPerCluster_ != (1 << clusterSizeShift_)) {
|
||||
while (blocksPerCluster_ != BIT(clusterSizeShift_)) {
|
||||
// error if not power of 2
|
||||
if (clusterSizeShift_++ > 7) goto fail;
|
||||
}
|
||||
|
|
|
@ -14,6 +14,7 @@
|
|||
#define BOARD_RAMPS_13_EEB 34 // RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Bed)
|
||||
#define BOARD_RAMPS_13_EFF 35 // RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Fan)
|
||||
#define BOARD_RAMPS_13_EEF 36 // RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Fan)
|
||||
#define BOARD_FELIX2 37 // Felix 2.0+ Electronics Board (RAMPS like)
|
||||
#define BOARD_DUEMILANOVE_328P 4 // Duemilanove w/ ATMega328P pin assignments
|
||||
#define BOARD_GEN6 5 // Gen6
|
||||
#define BOARD_GEN6_DELUXE 51 // Gen6 deluxe
|
||||
|
|
903
Marlin/configurator/config/Configuration.h
Normal file
|
@ -0,0 +1,903 @@
|
|||
#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://youtu.be/wAL9d7FgInk
|
||||
* http://calculator.josefprusa.cz
|
||||
* http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
|
||||
* http://www.thingiverse.com/thing:5573
|
||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||
* 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 ===============================
|
||||
//===========================================================================
|
||||
// For a Delta printer replace the configuration files with the files in the
|
||||
// example_configurations/delta directory.
|
||||
//
|
||||
|
||||
//===========================================================================
|
||||
//============================= SCARA Printer ===============================
|
||||
//===========================================================================
|
||||
// For a Delta printer replace the configuration files with the files in the
|
||||
// example_configurations/SCARA directory.
|
||||
//
|
||||
|
||||
// @section info
|
||||
|
||||
// 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 "1.0.2"
|
||||
#define STRING_URL "reprap.org"
|
||||
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
|
||||
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
|
||||
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
|
||||
//#define STRING_SPLASH_LINE2 STRING_VERSION_CONFIG_H // will be shown during bootup in line2
|
||||
|
||||
// @section machine
|
||||
|
||||
// SERIAL_PORT selects which serial port should be used for communication with the host.
|
||||
// This allows the connection of wireless adapters (for instance) to non-default port pins.
|
||||
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
|
||||
// :[0,1,2,3,4,5,6,7]
|
||||
#define SERIAL_PORT 0
|
||||
|
||||
// This determines the communication speed of the printer
|
||||
// :[2400,9600,19200,38400,57600,115200,250000]
|
||||
#define BAUDRATE 250000
|
||||
|
||||
// This enables the serial port associated to the Bluetooth interface
|
||||
//#define BTENABLED // Enable BT interface on AT90USB devices
|
||||
|
||||
// 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
|
||||
#endif
|
||||
|
||||
// Define this to set a custom name for your generic Mendel,
|
||||
// #define CUSTOM_MENDEL_NAME "This Mendel"
|
||||
|
||||
// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
|
||||
// You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
|
||||
// #define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
||||
|
||||
// This defines the number of extruders
|
||||
// :[1,2,3,4]
|
||||
#define EXTRUDERS 1
|
||||
|
||||
//// The following define selects which power supply you have. Please choose the one that matches your setup
|
||||
// 1 = ATX
|
||||
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
|
||||
// :{1:'ATX',2:'X-Box 360'}
|
||||
#define POWER_SUPPLY 1
|
||||
|
||||
// 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
|
||||
|
||||
// @section temperature
|
||||
|
||||
//===========================================================================
|
||||
//============================= Thermal Settings ============================
|
||||
//===========================================================================
|
||||
//
|
||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||
//
|
||||
//// Temperature sensor settings:
|
||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||
// -1 is thermocouple with AD595
|
||||
// 0 is not used
|
||||
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
|
||||
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
|
||||
// 3 is Mendel-parts thermistor (4.7k pullup)
|
||||
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
|
||||
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
|
||||
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
|
||||
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
|
||||
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
|
||||
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
|
||||
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
|
||||
// 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
|
||||
//
|
||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||
// (but gives greater accuracy and more stable PID)
|
||||
// 51 is 100k thermistor - EPCOS (1k pullup)
|
||||
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
|
||||
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
|
||||
//
|
||||
// 1047 is Pt1000 with 4k7 pullup
|
||||
// 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
|
||||
// :{ 0: "Not used", 4: "10k !! do not use for a hotend. Bad resolution at high temp. !!", 1: "100k / 4.7k - EPCOS", 51: "100k / 1k - EPCOS", 6: "100k / 4.7k EPCOS - Not as accurate as Table 1", 5: "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", 7: "100k / 4.7k Honeywell 135-104LAG-J01", 71: "100k / 4.7k Honeywell 135-104LAF-J01", 8: "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", 9: "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", 10: "100k / 4.7k RS 198-961", 11: "100k / 4.7k beta 3950 1%", 12: "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", 13: "100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", 60: "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", 55: "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", 2: "200k / 4.7k - ATC Semitec 204GT-2", 52: "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", 3: "Mendel-parts / 4.7k", 1047: "Pt1000 / 4.7k", 1010: "Pt1000 / 1k (non standard)", 20: "PT100 (Ultimainboard V2.x)", 147: "Pt100 / 4.7k", 110: "Pt100 / 1k (non-standard)", 998: "Dummy 1", 999: "Dummy 2" }
|
||||
#define TEMP_SENSOR_0 -1
|
||||
#define TEMP_SENSOR_1 -1
|
||||
#define TEMP_SENSOR_2 0
|
||||
#define TEMP_SENSOR_3 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
|
||||
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
|
||||
//#define TEMP_SENSOR_1_AS_REDUNDANT
|
||||
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
|
||||
|
||||
// Actual temperature must be close to target for this long before M109 returns success
|
||||
#define TEMP_RESIDENCY_TIME 10 // (seconds)
|
||||
#define TEMP_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one
|
||||
#define TEMP_WINDOW 1 // (degC) Window around target to start the residency timer x degC early.
|
||||
|
||||
// The minimal temperature defines the temperature below which the heater will not be enabled It is used
|
||||
// to check that the wiring to the thermistor is not broken.
|
||||
// Otherwise this would lead to the heater being powered on all the time.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
#define HEATER_1_MINTEMP 5
|
||||
#define HEATER_2_MINTEMP 5
|
||||
#define HEATER_3_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
|
||||
// When temperature exceeds max temp, your heater will be switched off.
|
||||
// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
|
||||
// You should use MINTEMP for thermistor short/failure protection.
|
||||
#define HEATER_0_MAXTEMP 275
|
||||
#define HEATER_1_MAXTEMP 275
|
||||
#define HEATER_2_MAXTEMP 275
|
||||
#define HEATER_3_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
|
||||
// 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.
|
||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
||||
|
||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||
//#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 ================================
|
||||
//===========================================================================
|
||||
// PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning
|
||||
|
||||
// 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 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 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
|
||||
|
||||
// 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
|
||||
|
||||
// MakerGear
|
||||
// #define DEFAULT_Kp 7.0
|
||||
// #define DEFAULT_Ki 0.1
|
||||
// #define DEFAULT_Kd 12
|
||||
|
||||
// Mendel Parts V9 on 12V
|
||||
// #define DEFAULT_Kp 63.0
|
||||
// #define DEFAULT_Ki 2.25
|
||||
// #define DEFAULT_Kd 440
|
||||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//===========================================================================
|
||||
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
|
||||
//
|
||||
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
|
||||
// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
|
||||
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
|
||||
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
|
||||
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
|
||||
// shouldn't use bed PID until someone else verifies your hardware works.
|
||||
// If this is enabled, find your own PID constants below.
|
||||
//#define PIDTEMPBED
|
||||
//
|
||||
//#define BED_LIMIT_SWITCHING
|
||||
|
||||
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||
|
||||
#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
|
||||
|
||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||
//from pidautotune
|
||||
// #define DEFAULT_bedKp 97.1
|
||||
// #define DEFAULT_bedKi 1.41
|
||||
// #define DEFAULT_bedKd 1675.16
|
||||
|
||||
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
||||
#endif // PIDTEMPBED
|
||||
|
||||
// @section extruder
|
||||
|
||||
//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
|
||||
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
|
||||
#define PREVENT_LENGTHY_EXTRUDE
|
||||
|
||||
#define EXTRUDE_MINTEMP 170
|
||||
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
|
||||
|
||||
//===========================================================================
|
||||
//============================= Thermal Runaway Protection ==================
|
||||
//===========================================================================
|
||||
/*
|
||||
This is a feature to protect your printer from burn up in flames if it has
|
||||
a thermistor coming off place (this happened to a friend of mine recently and
|
||||
motivated me writing this feature).
|
||||
|
||||
The issue: If a thermistor come off, it will read a lower temperature than actual.
|
||||
The system will turn the heater on forever, burning up the filament and anything
|
||||
else around.
|
||||
|
||||
After the temperature reaches the target for the first time, this feature will
|
||||
start measuring for how long the current temperature stays below the target
|
||||
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
|
||||
|
||||
If it stays longer than _PERIOD, it means the thermistor temperature
|
||||
cannot catch up with the target, so something *may be* wrong. Then, to be on the
|
||||
safe side, the system will he halt.
|
||||
|
||||
Bear in mind the count down will just start AFTER the first time the
|
||||
thermistor temperature is over the target, so you will have no problem if
|
||||
your extruder heater takes 2 minutes to hit the target on heating.
|
||||
|
||||
*/
|
||||
// If you want to enable this feature for all your extruder heaters,
|
||||
// uncomment the 2 defines below:
|
||||
|
||||
// Parameters for all extruder heaters
|
||||
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
|
||||
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
|
||||
|
||||
// If you want to enable this feature for your bed heater,
|
||||
// uncomment the 2 defines below:
|
||||
|
||||
// Parameters for the bed heater
|
||||
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
|
||||
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
|
||||
|
||||
|
||||
//===========================================================================
|
||||
//============================= Mechanical Settings =========================
|
||||
//===========================================================================
|
||||
|
||||
// @section machine
|
||||
|
||||
// Uncomment this option to enable CoreXY kinematics
|
||||
// #define COREXY
|
||||
|
||||
// Enable this option for Toshiba steppers
|
||||
// #define CONFIG_STEPPERS_TOSHIBA
|
||||
|
||||
// @section homing
|
||||
|
||||
// coarse Endstop Settings
|
||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||
|
||||
#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
|
||||
|
||||
#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.
|
||||
//#define DISABLE_MAX_ENDSTOPS
|
||||
//#define DISABLE_MIN_ENDSTOPS
|
||||
|
||||
// @section machine
|
||||
|
||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||
// :{0:'Low',1:'High'}
|
||||
#define X_ENABLE_ON 0
|
||||
#define Y_ENABLE_ON 0
|
||||
#define Z_ENABLE_ON 0
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
|
||||
// @section extruder
|
||||
|
||||
#define DISABLE_E false // For all extruders
|
||||
#define DISABLE_INACTIVE_EXTRUDER true //disable only inactive extruders and keep active extruder enabled
|
||||
|
||||
// @section machine
|
||||
|
||||
// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
|
||||
#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
|
||||
|
||||
// @section extruder
|
||||
|
||||
// For direct drive extruder v9 set to true, for geared extruder set to false.
|
||||
#define INVERT_E0_DIR false // Direct drive extruder v9: true. Geared extruder: false
|
||||
#define INVERT_E1_DIR false // Direct drive extruder v9: true. Geared extruder: false
|
||||
#define INVERT_E2_DIR false // Direct drive extruder v9: true. Geared extruder: false
|
||||
#define INVERT_E3_DIR false // Direct drive extruder v9: true. Geared extruder: false
|
||||
|
||||
// @section homing
|
||||
|
||||
// ENDSTOP SETTINGS:
|
||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||
// :[-1,1]
|
||||
#define X_HOME_DIR -1
|
||||
#define Y_HOME_DIR -1
|
||||
#define Z_HOME_DIR -1
|
||||
|
||||
#define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
|
||||
#define max_software_endstops true // If true, axis won't move to coordinates greater than the defined lengths below.
|
||||
|
||||
// @section machine
|
||||
|
||||
// Travel limits after homing (units are in mm)
|
||||
#define X_MIN_POS 0
|
||||
#define Y_MIN_POS 0
|
||||
#define Z_MIN_POS 0
|
||||
#define X_MAX_POS 205
|
||||
#define Y_MAX_POS 205
|
||||
#define Z_MAX_POS 200
|
||||
|
||||
// @section hidden
|
||||
|
||||
#define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)
|
||||
#define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
|
||||
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
|
||||
|
||||
|
||||
//===========================================================================
|
||||
//============================= Bed Auto Leveling ===========================
|
||||
//===========================================================================
|
||||
|
||||
// @section bedlevel
|
||||
|
||||
//#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 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
|
||||
|
||||
#ifdef AUTO_BED_LEVELING_GRID
|
||||
|
||||
// Use one of these defines to specify the origin
|
||||
// for a topographical map to be printed for your bed.
|
||||
enum { OriginBackLeft, OriginFrontLeft, OriginBackRight, OriginFrontRight };
|
||||
#define TOPO_ORIGIN OriginFrontLeft
|
||||
|
||||
// The edges of the rectangle in which to probe
|
||||
#define LEFT_PROBE_BED_POSITION 15
|
||||
#define RIGHT_PROBE_BED_POSITION 170
|
||||
#define FRONT_PROBE_BED_POSITION 20
|
||||
#define BACK_PROBE_BED_POSITION 170
|
||||
|
||||
// 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 // !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
|
||||
#define ABL_PROBE_PT_2_Y 20
|
||||
#define ABL_PROBE_PT_3_X 170
|
||||
#define ABL_PROBE_PT_3_Y 20
|
||||
|
||||
#endif // AUTO_BED_LEVELING_GRID
|
||||
|
||||
|
||||
// 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
|
||||
|
||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min
|
||||
|
||||
#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.
|
||||
// You MUST HAVE the SERVO_ENDSTOPS defined to use here a value higher than zero otherwise your code will not compile.
|
||||
|
||||
// #define PROBE_SERVO_DEACTIVATION_DELAY 300
|
||||
|
||||
|
||||
//If you have enabled the Bed Auto Leveling and are using the same Z Probe for Z Homing,
|
||||
//it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
||||
|
||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with probe outside the bed area.
|
||||
// When defined, it will:
|
||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled
|
||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing
|
||||
// - Position the probe in a defined XY point before Z Homing when homing all axis (G28)
|
||||
// - Block Z homing only when the probe is outside bed area.
|
||||
|
||||
#ifdef Z_SAFE_HOMING
|
||||
|
||||
#define Z_SAFE_HOMING_X_POINT (X_MAX_LENGTH/2) // X point for Z homing when homing all axis (G28)
|
||||
#define Z_SAFE_HOMING_Y_POINT (Y_MAX_LENGTH/2) // Y point for Z homing when homing all axis (G28)
|
||||
|
||||
#endif
|
||||
|
||||
#endif // ENABLE_AUTO_BED_LEVELING
|
||||
|
||||
|
||||
// @section homing
|
||||
|
||||
// The position of the homing switches
|
||||
//#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:
|
||||
// For deltabots this means top and center of the Cartesian print volume.
|
||||
#ifdef MANUAL_HOME_POSITIONS
|
||||
#define MANUAL_X_HOME_POS 0
|
||||
#define MANUAL_Y_HOME_POS 0
|
||||
#define MANUAL_Z_HOME_POS 0
|
||||
//#define MANUAL_Z_HOME_POS 402 // For delta: Distance between nozzle and print surface after homing.
|
||||
#endif
|
||||
|
||||
// @section movement
|
||||
|
||||
//// MOVEMENT SETTINGS
|
||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||
#define HOMING_FEEDRATE {50*60, 50*60, 4*60, 0} // set the homing speeds (mm/min)
|
||||
|
||||
// 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_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
|
||||
|
||||
// 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).
|
||||
// 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
|
||||
|
||||
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
|
||||
#define DEFAULT_XYJERK 20.0 // (mm/sec)
|
||||
#define DEFAULT_ZJERK 0.4 // (mm/sec)
|
||||
#define DEFAULT_EJERK 5.0 // (mm/sec)
|
||||
|
||||
|
||||
//=============================================================================
|
||||
//============================= Additional Features ===========================
|
||||
//=============================================================================
|
||||
|
||||
// @section more
|
||||
|
||||
// Custom M code points
|
||||
#define CUSTOM_M_CODES
|
||||
#ifdef CUSTOM_M_CODES
|
||||
#define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
|
||||
#define Z_PROBE_OFFSET_RANGE_MIN -15
|
||||
#define Z_PROBE_OFFSET_RANGE_MAX -5
|
||||
#endif
|
||||
|
||||
// @section extras
|
||||
|
||||
// EEPROM
|
||||
// The microcontroller can store settings in the EEPROM, e.g. max velocity...
|
||||
// M500 - stores parameters in EEPROM
|
||||
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
||||
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
||||
//define this to enable EEPROM support
|
||||
//#define EEPROM_SETTINGS
|
||||
//to disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
|
||||
// please keep turned on if you can.
|
||||
//#define EEPROM_CHITCHAT
|
||||
|
||||
// @section temperature
|
||||
|
||||
// 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 ABS_PREHEAT_HOTEND_TEMP 240
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
|
||||
|
||||
//==============================LCD and SD support=============================
|
||||
// @section lcd
|
||||
|
||||
// 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°"
|
||||
//#define DISPLAY_CHARSET_HD44780_WESTERN // "ÄäÖöÜüß²³°" if you see a '~' instead of a 'arrow_right' at the right of submenuitems - this is the right one.
|
||||
|
||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||
//#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 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
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
//#define PANEL_ONE
|
||||
|
||||
// The MaKr3d Makr-Panel with graphic controller and SD support
|
||||
// http://reprap.org/wiki/MaKr3d_MaKrPanel
|
||||
//#define MAKRPANEL
|
||||
|
||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||
// http://panucatt.com
|
||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
||||
//#define VIKI2
|
||||
//#define miniVIKI
|
||||
|
||||
// The RepRapDiscount Smart Controller (white PCB)
|
||||
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
|
||||
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||
|
||||
// The GADGETS3D G3D LCD/SD Controller (blue PCB)
|
||||
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
|
||||
//#define G3D_PANEL
|
||||
|
||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||
//
|
||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||
|
||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
|
||||
//#define REPRAPWORLD_KEYPAD
|
||||
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // how much should be moved when a key is pressed, eg 10.0 means 10mm per click
|
||||
|
||||
// The Elefu RA Board Control Panel
|
||||
// http://www.elefu.com/index.php?route=product/product&product_id=53
|
||||
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
||||
//#define RA_CONTROL_PANEL
|
||||
|
||||
// @section hidden
|
||||
|
||||
//automatic expansion
|
||||
#if defined (MAKRPANEL)
|
||||
#define DOGLCD
|
||||
#define SDSUPPORT
|
||||
#define ULTIPANEL
|
||||
#define NEWPANEL
|
||||
#define DEFAULT_LCD_CONTRAST 17
|
||||
#endif
|
||||
|
||||
#if defined(miniVIKI) || defined(VIKI2)
|
||||
#define ULTRA_LCD //general LCD support, also 16x2
|
||||
#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||
#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
|
||||
#ifdef miniVIKI
|
||||
#define DEFAULT_LCD_CONTRAST 95
|
||||
#else
|
||||
#define DEFAULT_LCD_CONTRAST 40
|
||||
#endif
|
||||
|
||||
#define ENCODER_PULSES_PER_STEP 4
|
||||
#define ENCODER_STEPS_PER_MENU_ITEM 1
|
||||
#endif
|
||||
|
||||
#if defined (PANEL_ONE)
|
||||
#define SDSUPPORT
|
||||
#define ULTIMAKERCONTROLLER
|
||||
#endif
|
||||
|
||||
#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
|
||||
#define DOGLCD
|
||||
#define U8GLIB_ST7920
|
||||
#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||
#endif
|
||||
|
||||
#if defined(ULTIMAKERCONTROLLER) || defined(REPRAP_DISCOUNT_SMART_CONTROLLER) || defined(G3D_PANEL)
|
||||
#define ULTIPANEL
|
||||
#define NEWPANEL
|
||||
#endif
|
||||
|
||||
#if defined(REPRAPWORLD_KEYPAD)
|
||||
#define NEWPANEL
|
||||
#define ULTIPANEL
|
||||
#endif
|
||||
#if defined(RA_CONTROL_PANEL)
|
||||
#define ULTIPANEL
|
||||
#define NEWPANEL
|
||||
#define LCD_I2C_TYPE_PCA8574
|
||||
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
|
||||
#endif
|
||||
|
||||
//I2C PANELS
|
||||
|
||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||
#ifdef LCD_I2C_SAINSMART_YWROBOT
|
||||
// This uses the LiquidCrystal_I2C library ( https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home )
|
||||
// Make sure it is placed in the Arduino libraries directory.
|
||||
#define LCD_I2C_TYPE_PCF8575
|
||||
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
|
||||
#define NEWPANEL
|
||||
#define ULTIPANEL
|
||||
#endif
|
||||
|
||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||
//#define LCD_I2C_PANELOLU2
|
||||
#ifdef LCD_I2C_PANELOLU2
|
||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
|
||||
// (v1.2.3 no longer requires you to define PANELOLU in the LiquidTWI2.h library header file)
|
||||
// Note: The PANELOLU2 encoder click input can either be directly connected to a pin
|
||||
// (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1).
|
||||
#define LCD_I2C_TYPE_MCP23017
|
||||
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
|
||||
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD
|
||||
#define NEWPANEL
|
||||
#define ULTIPANEL
|
||||
|
||||
#ifndef ENCODER_PULSES_PER_STEP
|
||||
#define ENCODER_PULSES_PER_STEP 4
|
||||
#endif
|
||||
|
||||
#ifndef ENCODER_STEPS_PER_MENU_ITEM
|
||||
#define ENCODER_STEPS_PER_MENU_ITEM 1
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef LCD_USE_I2C_BUZZER
|
||||
#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
||||
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
// Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
|
||||
//#define LCD_I2C_VIKI
|
||||
#ifdef LCD_I2C_VIKI
|
||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
|
||||
// Note: The pause/stop/resume LCD button pin should be connected to the Arduino
|
||||
// BTN_ENC pin (or set BTN_ENC to -1 if not used)
|
||||
#define LCD_I2C_TYPE_MCP23017
|
||||
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
|
||||
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later)
|
||||
#define NEWPANEL
|
||||
#define ULTIPANEL
|
||||
#endif
|
||||
|
||||
// Shift register panels
|
||||
// ---------------------
|
||||
// 2 wire Non-latching LCD SR from:
|
||||
// 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
|
||||
|
||||
|
||||
#ifdef ULTIPANEL
|
||||
// #define NEWPANEL //enable this if you have a click-encoder panel
|
||||
#define SDSUPPORT
|
||||
#define ULTRA_LCD
|
||||
#ifdef DOGLCD // Change number of lines to match the DOG graphic display
|
||||
#define LCD_WIDTH 22
|
||||
#define LCD_HEIGHT 5
|
||||
#else
|
||||
#define LCD_WIDTH 20
|
||||
#define LCD_HEIGHT 4
|
||||
#endif
|
||||
#else //no panel but just LCD
|
||||
#ifdef ULTRA_LCD
|
||||
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
|
||||
#define LCD_WIDTH 22
|
||||
#define LCD_HEIGHT 5
|
||||
#else
|
||||
#define LCD_WIDTH 16
|
||||
#define LCD_HEIGHT 2
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// @section lcd
|
||||
|
||||
// default LCD contrast for dogm-like LCD displays
|
||||
#ifdef DOGLCD
|
||||
# ifndef DEFAULT_LCD_CONTRAST
|
||||
# define DEFAULT_LCD_CONTRAST 32
|
||||
# endif
|
||||
#endif
|
||||
|
||||
// @section extras
|
||||
|
||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||
//#define FAST_PWM_FAN
|
||||
|
||||
// Temperature status LEDs that display the hotend and bet temperature.
|
||||
// If all hotends and bed temperature and temperature setpoint are < 54C then the BLUE led is on.
|
||||
// Otherwise the RED led is on. There is 1C hysteresis.
|
||||
//#define TEMP_STAT_LEDS
|
||||
|
||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||
// which is not ass annoying as with the hardware PWM. On the other hand, if this frequency
|
||||
// is too low, you should also increment SOFT_PWM_SCALE.
|
||||
//#define FAN_SOFT_PWM
|
||||
|
||||
// Incrementing this by 1 will double the software PWM frequency,
|
||||
// affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
|
||||
// However, control resolution will be halved for each increment;
|
||||
// at zero value, there are 128 effective control positions.
|
||||
#define SOFT_PWM_SCALE 0
|
||||
|
||||
// M240 Triggers a camera by emulating a Canon RC-1 Remote
|
||||
// Data from: http://www.doc-diy.net/photo/rc-1_hacked/
|
||||
// #define PHOTOGRAPH_PIN 23
|
||||
|
||||
// SF send wrong arc g-codes when using Arc Point as fillet procedure
|
||||
//#define SF_ARC_FIX
|
||||
|
||||
// Support for the BariCUDA Paste Extruder.
|
||||
//#define BARICUDA
|
||||
|
||||
//define BlinkM/CyzRgb Support
|
||||
//#define BLINKM
|
||||
|
||||
/*********************************************************************\
|
||||
* R/C SERVO support
|
||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||
**********************************************************************/
|
||||
|
||||
// Number of servos
|
||||
//
|
||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
||||
// set it manually if you have more servos than extruders and wish to manually control some
|
||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
||||
// If unsure, leave commented / disabled
|
||||
//
|
||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||
|
||||
// Servo Endstops
|
||||
//
|
||||
// This allows for servo actuated endstops, primary usage is for the Z Axis to eliminate calibration or bed height changes.
|
||||
// Use M206 command to correct for switch height offset to actual nozzle height. Store that setting with M500.
|
||||
//
|
||||
//#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1
|
||||
//#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 70,0} // X,Y,Z Axis Extend and Retract angles
|
||||
|
||||
/**********************************************************************\
|
||||
* Support for a filament diameter sensor
|
||||
* Also allows adjustment of diameter at print time (vs at slicing)
|
||||
* Single extruder only at this point (extruder 0)
|
||||
*
|
||||
* Motherboards
|
||||
* 34 - RAMPS1.4 - uses Analog input 5 on the AUX2 connector
|
||||
* 81 - Printrboard - Uses Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||
* 301 - Rambo - uses Analog input 3
|
||||
* Note may require analog pins to be defined for different motherboards
|
||||
**********************************************************************/
|
||||
// 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 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)
|
||||
|
||||
//defines used in the code
|
||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||
|
||||
//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status. Status will appear for 5 sec.
|
||||
//#define FILAMENT_LCD_DISPLAY
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#include "Configuration_adv.h"
|
||||
#include "thermistortables.h"
|
||||
|
||||
#endif //__CONFIGURATION_H
|
584
Marlin/configurator/config/Configuration_adv.h
Normal file
|
@ -0,0 +1,584 @@
|
|||
#ifndef CONFIGURATION_ADV_H
|
||||
#define CONFIGURATION_ADV_H
|
||||
|
||||
// @section temperature
|
||||
|
||||
//===========================================================================
|
||||
//=============================Thermal Settings ============================
|
||||
//===========================================================================
|
||||
|
||||
#ifdef BED_LIMIT_SWITCHING
|
||||
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||
#endif
|
||||
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
|
||||
|
||||
//// Heating sanity check:
|
||||
// This waits for the watch period in milliseconds whenever an M104 or M109 increases the target temperature
|
||||
// If the temperature has not increased at the end of that period, the target temperature is set to zero.
|
||||
// It can be reset with another M104/M109. This check is also only triggered if the target temperature and the current temperature
|
||||
// differ by at least 2x WATCH_TEMP_INCREASE
|
||||
//#define WATCH_TEMP_PERIOD 40000 //40 seconds
|
||||
//#define WATCH_TEMP_INCREASE 10 //Heat up at least 10 degree in 20 seconds
|
||||
|
||||
#ifdef PIDTEMP
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
#define PID_ADD_EXTRUSION_RATE
|
||||
#ifdef PID_ADD_EXTRUSION_RATE
|
||||
#define DEFAULT_Kc (1) //heating power=Kc*(e_speed)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
|
||||
//The maximum buffered steps/sec of the extruder motor are called "se".
|
||||
//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
|
||||
// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
|
||||
// you exit the value by any M109 without F*
|
||||
// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
|
||||
// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||
#define AUTOTEMP
|
||||
#ifdef AUTOTEMP
|
||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||
#endif
|
||||
|
||||
//Show Temperature ADC value
|
||||
//The M105 command return, besides traditional information, the ADC value read from temperature sensors.
|
||||
//#define SHOW_TEMP_ADC_VALUES
|
||||
|
||||
// @section extruder
|
||||
|
||||
// extruder run-out prevention.
|
||||
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
|
||||
//#define EXTRUDER_RUNOUT_PREVENT
|
||||
#define EXTRUDER_RUNOUT_MINTEMP 190
|
||||
#define EXTRUDER_RUNOUT_SECONDS 30.
|
||||
#define EXTRUDER_RUNOUT_ESTEPS 14. //mm filament
|
||||
#define EXTRUDER_RUNOUT_SPEED 1500. //extrusion speed
|
||||
#define EXTRUDER_RUNOUT_EXTRUDE 100
|
||||
|
||||
// @section temperature
|
||||
|
||||
//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
|
||||
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
|
||||
#define TEMP_SENSOR_AD595_OFFSET 0.0
|
||||
#define TEMP_SENSOR_AD595_GAIN 1.0
|
||||
|
||||
//This is for controlling a fan to cool down the stepper drivers
|
||||
//it will turn on when any driver is enabled
|
||||
//and turn off after the set amount of seconds from last driver being disabled again
|
||||
#define CONTROLLERFAN_PIN -1 //Pin used for the fan to cool controller (-1 to disable)
|
||||
#define CONTROLLERFAN_SECS 60 //How many seconds, after all motors were disabled, the fan should run
|
||||
#define CONTROLLERFAN_SPEED 255 // == full speed
|
||||
|
||||
// When first starting the main fan, run it at full speed for the
|
||||
// given number of milliseconds. This gets the fan spinning reliably
|
||||
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
|
||||
//#define FAN_KICKSTART_TIME 100
|
||||
|
||||
// @section extruder
|
||||
|
||||
// Extruder cooling fans
|
||||
// Configure fan pin outputs to automatically turn on/off when the associated
|
||||
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
|
||||
// Multiple extruders can be assigned to the same pin in which case
|
||||
// the fan will turn on when any selected extruder is above the threshold.
|
||||
#define EXTRUDER_0_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_1_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_2_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_3_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
|
||||
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
|
||||
|
||||
|
||||
//===========================================================================
|
||||
//=============================Mechanical Settings===========================
|
||||
//===========================================================================
|
||||
|
||||
// @section homing
|
||||
|
||||
#define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing
|
||||
|
||||
|
||||
// @section hidden
|
||||
|
||||
|
||||
//// AUTOSET LOCATIONS OF LIMIT SWITCHES
|
||||
//// Added by ZetaPhoenix 09-15-2012
|
||||
#ifdef MANUAL_HOME_POSITIONS // Use manual limit switch locations
|
||||
#define X_HOME_POS MANUAL_X_HOME_POS
|
||||
#define Y_HOME_POS MANUAL_Y_HOME_POS
|
||||
#define Z_HOME_POS MANUAL_Z_HOME_POS
|
||||
#else //Set min/max homing switch positions based upon homing direction and min/max travel limits
|
||||
//X axis
|
||||
#if X_HOME_DIR == -1
|
||||
#ifdef BED_CENTER_AT_0_0
|
||||
#define X_HOME_POS X_MAX_LENGTH * -0.5
|
||||
#else
|
||||
#define X_HOME_POS X_MIN_POS
|
||||
#endif //BED_CENTER_AT_0_0
|
||||
#else
|
||||
#ifdef BED_CENTER_AT_0_0
|
||||
#define X_HOME_POS X_MAX_LENGTH * 0.5
|
||||
#else
|
||||
#define X_HOME_POS X_MAX_POS
|
||||
#endif //BED_CENTER_AT_0_0
|
||||
#endif //X_HOME_DIR == -1
|
||||
|
||||
//Y axis
|
||||
#if Y_HOME_DIR == -1
|
||||
#ifdef BED_CENTER_AT_0_0
|
||||
#define Y_HOME_POS Y_MAX_LENGTH * -0.5
|
||||
#else
|
||||
#define Y_HOME_POS Y_MIN_POS
|
||||
#endif //BED_CENTER_AT_0_0
|
||||
#else
|
||||
#ifdef BED_CENTER_AT_0_0
|
||||
#define Y_HOME_POS Y_MAX_LENGTH * 0.5
|
||||
#else
|
||||
#define Y_HOME_POS Y_MAX_POS
|
||||
#endif //BED_CENTER_AT_0_0
|
||||
#endif //Y_HOME_DIR == -1
|
||||
|
||||
// Z axis
|
||||
#if Z_HOME_DIR == -1 //BED_CENTER_AT_0_0 not used
|
||||
#define Z_HOME_POS Z_MIN_POS
|
||||
#else
|
||||
#define Z_HOME_POS Z_MAX_POS
|
||||
#endif //Z_HOME_DIR == -1
|
||||
#endif //End auto min/max positions
|
||||
//END AUTOSET LOCATIONS OF LIMIT SWITCHES -ZP
|
||||
|
||||
// @section extras
|
||||
|
||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||
|
||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
||||
// Uncomment this define to utilize a separate stepper driver for each Z axis motor.
|
||||
// Only a few motherboards support this, like RAMPS, which have dual extruder support (the 2nd, often unused, extruder driver is used
|
||||
// to control the 2nd Z axis stepper motor). The pins are currently only defined for a RAMPS motherboards.
|
||||
// On a RAMPS (or other 5 driver) motherboard, using this feature will limit you to using 1 extruder.
|
||||
//#define Z_DUAL_STEPPER_DRIVERS
|
||||
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
#undef EXTRUDERS
|
||||
#define EXTRUDERS 1
|
||||
#endif
|
||||
|
||||
// Same again but for Y Axis.
|
||||
//#define Y_DUAL_STEPPER_DRIVERS
|
||||
|
||||
// Define if the two Y drives need to rotate in opposite directions
|
||||
#define INVERT_Y2_VS_Y_DIR true
|
||||
|
||||
#ifdef Y_DUAL_STEPPER_DRIVERS
|
||||
#undef EXTRUDERS
|
||||
#define EXTRUDERS 1
|
||||
#endif
|
||||
|
||||
#if defined (Z_DUAL_STEPPER_DRIVERS) && defined (Y_DUAL_STEPPER_DRIVERS)
|
||||
#error "You cannot have dual drivers for both Y and Z"
|
||||
#endif
|
||||
|
||||
// Enable this for dual x-carriage printers.
|
||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
|
||||
// allowing faster printing speeds.
|
||||
//#define DUAL_X_CARRIAGE
|
||||
#ifdef DUAL_X_CARRIAGE
|
||||
// Configuration for second X-carriage
|
||||
// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
|
||||
// the second x-carriage always homes to the maximum endstop.
|
||||
#define X2_MIN_POS 80 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
|
||||
#define X2_MAX_POS 353 // set maximum to the distance between toolheads when both heads are homed
|
||||
#define X2_HOME_DIR 1 // the second X-carriage always homes to the maximum endstop position
|
||||
#define X2_HOME_POS X2_MAX_POS // default home position is the maximum carriage position
|
||||
// However: In this mode the EXTRUDER_OFFSET_X value for the second extruder provides a software
|
||||
// override for X2_HOME_POS. This also allow recalibration of the distance between the two endstops
|
||||
// without modifying the firmware (through the "M218 T1 X???" command).
|
||||
// Remember: you should set the second extruder x-offset to 0 in your slicer.
|
||||
|
||||
// Pins for second x-carriage stepper driver (defined here to avoid further complicating pins.h)
|
||||
#define X2_ENABLE_PIN 29
|
||||
#define X2_STEP_PIN 25
|
||||
#define X2_DIR_PIN 23
|
||||
|
||||
// There are a few selectable movement modes for dual x-carriages using M605 S<mode>
|
||||
// Mode 0: Full control. The slicer has full control over both x-carriages and can achieve optimal travel results
|
||||
// as long as it supports dual x-carriages. (M605 S0)
|
||||
// Mode 1: Auto-park mode. The firmware will automatically park and unpark the x-carriages on tool changes so
|
||||
// that additional slicer support is not required. (M605 S1)
|
||||
// Mode 2: Duplication mode. The firmware will transparently make the second x-carriage and extruder copy all
|
||||
// actions of the first x-carriage. This allows the printer to print 2 arbitrary items at
|
||||
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
|
||||
|
||||
// This is the default power-up mode which can be later using M605.
|
||||
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
|
||||
|
||||
// Default settings in "Auto-park Mode"
|
||||
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
|
||||
#define TOOLCHANGE_UNPARK_ZLIFT 1 // the distance to raise Z axis when unparking an extruder
|
||||
|
||||
// Default x offset in duplication mode (typically set to half print bed width)
|
||||
#define DEFAULT_DUPLICATION_X_OFFSET 100
|
||||
|
||||
#endif //DUAL_X_CARRIAGE
|
||||
|
||||
// @section homing
|
||||
|
||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
||||
#define X_HOME_RETRACT_MM 5
|
||||
#define Y_HOME_RETRACT_MM 5
|
||||
#define Z_HOME_RETRACT_MM 2
|
||||
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
|
||||
|
||||
// @section machine
|
||||
|
||||
#define AXIS_RELATIVE_MODES {false, false, false, false}
|
||||
|
||||
// @section hidden
|
||||
|
||||
#ifdef CONFIG_STEPPERS_TOSHIBA
|
||||
#define MAX_STEP_FREQUENCY 10000 // Max step frequency for Toshiba Stepper Controllers
|
||||
#else
|
||||
#define MAX_STEP_FREQUENCY 40000 // Max step frequency for Ultimaker (5000 pps / half step)
|
||||
#endif
|
||||
|
||||
// @section machine
|
||||
|
||||
//By default pololu step drivers require an active high signal. However, some high power drivers require an active low signal as step.
|
||||
#define INVERT_X_STEP_PIN false
|
||||
#define INVERT_Y_STEP_PIN false
|
||||
#define INVERT_Z_STEP_PIN false
|
||||
#define INVERT_E_STEP_PIN false
|
||||
|
||||
//default stepper release if idle. Set to 0 to deactivate.
|
||||
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
||||
|
||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||
|
||||
// @section lcd
|
||||
|
||||
// Feedrates for manual moves along X, Y, Z, E from panel
|
||||
#ifdef ULTIPANEL
|
||||
#define MANUAL_FEEDRATE {50*60, 50*60, 4*60, 60} // set the speeds for manual moves (mm/min)
|
||||
#endif
|
||||
|
||||
//Comment to disable setting feedrate multiplier via encoder
|
||||
#ifdef ULTIPANEL
|
||||
#define ULTIPANEL_FEEDMULTIPLY
|
||||
#endif
|
||||
|
||||
// @section extras
|
||||
|
||||
// minimum time in microseconds that a movement needs to take if the buffer is emptied.
|
||||
#define DEFAULT_MINSEGMENTTIME 20000
|
||||
|
||||
// If defined the movements slow down when the look ahead buffer is only half full
|
||||
#define SLOWDOWN
|
||||
|
||||
// Frequency limit
|
||||
// See nophead's blog for more info
|
||||
// Not working O
|
||||
//#define XY_FREQUENCY_LIMIT 15
|
||||
|
||||
// Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
|
||||
// of the buffer and all stops. This should not be much greater than zero and should only be changed
|
||||
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
|
||||
#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
|
||||
|
||||
// MS1 MS2 Stepper Driver Microstepping mode table
|
||||
#define MICROSTEP1 LOW,LOW
|
||||
#define MICROSTEP2 HIGH,LOW
|
||||
#define MICROSTEP4 LOW,HIGH
|
||||
#define MICROSTEP8 HIGH,HIGH
|
||||
#define MICROSTEP16 HIGH,HIGH
|
||||
|
||||
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
|
||||
#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
|
||||
|
||||
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||
|
||||
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
||||
//#define DIGIPOT_I2C
|
||||
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
||||
#define DIGIPOT_I2C_NUM_CHANNELS 8
|
||||
// actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||
#define DIGIPOT_I2C_MOTOR_CURRENTS {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0}
|
||||
|
||||
//===========================================================================
|
||||
//=============================Additional Features===========================
|
||||
//===========================================================================
|
||||
|
||||
#define ENCODER_RATE_MULTIPLIER // If defined, certain menu edit operations automatically multiply the steps when the encoder is moved quickly
|
||||
#define ENCODER_10X_STEPS_PER_SEC 75 // If the encoder steps per sec exceed this value, multiple the steps moved by ten to quickly advance the value
|
||||
#define ENCODER_100X_STEPS_PER_SEC 160 // If the encoder steps per sec exceed this value, multiple the steps moved by 100 to really quickly advance the value
|
||||
//#define ENCODER_RATE_MULTIPLIER_DEBUG // If defined, output the encoder steps per second value
|
||||
|
||||
//#define CHDK 4 //Pin for triggering CHDK to take a picture see how to use it here http://captain-slow.dk/2014/03/09/3d-printing-timelapses/
|
||||
#define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
|
||||
|
||||
// @section lcd
|
||||
|
||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
||||
#define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
|
||||
|
||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
||||
// if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
|
||||
// using:
|
||||
//#define MENU_ADDAUTOSTART
|
||||
|
||||
// Show a progress bar on HD44780 LCDs for SD printing
|
||||
//#define LCD_PROGRESS_BAR
|
||||
|
||||
#ifdef LCD_PROGRESS_BAR
|
||||
// Amount of time (ms) to show the bar
|
||||
#define PROGRESS_BAR_BAR_TIME 2000
|
||||
// Amount of time (ms) to show the status message
|
||||
#define PROGRESS_BAR_MSG_TIME 3000
|
||||
// Amount of time (ms) to retain the status message (0=forever)
|
||||
#define PROGRESS_MSG_EXPIRE 0
|
||||
// Enable this to show messages for MSG_TIME then hide them
|
||||
//#define PROGRESS_MSG_ONCE
|
||||
#ifdef DOGLCD
|
||||
#warning LCD_PROGRESS_BAR does not apply to graphical displays at this time.
|
||||
#endif
|
||||
#ifdef FILAMENT_LCD_DISPLAY
|
||||
#error LCD_PROGRESS_BAR and FILAMENT_LCD_DISPLAY are not fully compatible. Comment out this line to use both.
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// @section more
|
||||
|
||||
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
||||
//#define USE_WATCHDOG
|
||||
|
||||
#ifdef USE_WATCHDOG
|
||||
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||
// However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
|
||||
//#define WATCHDOG_RESET_MANUAL
|
||||
#endif
|
||||
|
||||
// Enable the option to stop SD printing when hitting and endstops, needs to be enabled from the LCD menu when this option is enabled.
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
// Babystepping enables the user to control the axis in tiny amounts, independently from the normal printing process
|
||||
// it can e.g. be used to change z-positions in the print startup phase in real-time
|
||||
// does not respect endstops!
|
||||
//#define BABYSTEPPING
|
||||
#ifdef BABYSTEPPING
|
||||
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
||||
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
||||
#define BABYSTEP_Z_MULTIPLICATOR 2 //faster z movements
|
||||
|
||||
#ifdef COREXY
|
||||
#error BABYSTEPPING not implemented for COREXY yet.
|
||||
#endif
|
||||
|
||||
#ifdef DELTA
|
||||
#ifdef BABYSTEP_XY
|
||||
#error BABYSTEPPING only implemented for Z axis on deltabots.
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// extruder advance constant (s2/mm3)
|
||||
//
|
||||
// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
|
||||
//
|
||||
// Hooke's law says: force = k * distance
|
||||
// Bernoulli's principle says: v ^ 2 / 2 + g . h + pressure / density = constant
|
||||
// so: v ^ 2 is proportional to number of steps we advance the extruder
|
||||
//#define ADVANCE
|
||||
|
||||
#ifdef ADVANCE
|
||||
#define EXTRUDER_ADVANCE_K .0
|
||||
|
||||
#define D_FILAMENT 2.85
|
||||
#define STEPS_MM_E 836
|
||||
#define EXTRUSION_AREA (0.25 * D_FILAMENT * D_FILAMENT * 3.14159)
|
||||
#define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS]/ EXTRUSION_AREA)
|
||||
|
||||
#endif // ADVANCE
|
||||
|
||||
// Arc interpretation settings:
|
||||
#define MM_PER_ARC_SEGMENT 1
|
||||
#define N_ARC_CORRECTION 25
|
||||
|
||||
const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
||||
|
||||
// @section lcd
|
||||
|
||||
// If you are using a RAMPS board or cheap E-bay purchased boards that do not detect when an SD card is inserted
|
||||
// You can get round this by connecting a push button or single throw switch to the pin defined as SDCARDCARDDETECT
|
||||
// in the pins.h file. When using a push button pulling the pin to ground this will need inverted. This setting should
|
||||
// be commented out otherwise
|
||||
#define SDCARDDETECTINVERTED
|
||||
|
||||
// @section hidden
|
||||
|
||||
#ifdef ULTIPANEL
|
||||
#undef SDCARDDETECTINVERTED
|
||||
#endif
|
||||
|
||||
// Power Signal Control Definitions
|
||||
// By default use ATX definition
|
||||
#ifndef POWER_SUPPLY
|
||||
#define POWER_SUPPLY 1
|
||||
#endif
|
||||
// 1 = ATX
|
||||
#if (POWER_SUPPLY == 1)
|
||||
#define PS_ON_AWAKE LOW
|
||||
#define PS_ON_ASLEEP HIGH
|
||||
#endif
|
||||
// 2 = X-Box 360 203W
|
||||
#if (POWER_SUPPLY == 2)
|
||||
#define PS_ON_AWAKE HIGH
|
||||
#define PS_ON_ASLEEP LOW
|
||||
#endif
|
||||
|
||||
// @section temperature
|
||||
|
||||
// Control heater 0 and heater 1 in parallel.
|
||||
//#define HEATERS_PARALLEL
|
||||
|
||||
//===========================================================================
|
||||
//=============================Buffers ============================
|
||||
//===========================================================================
|
||||
|
||||
// @section hidden
|
||||
|
||||
// The number of linear motions that can be in the plan at any give time.
|
||||
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
|
||||
#if defined SDSUPPORT
|
||||
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
|
||||
#else
|
||||
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
|
||||
#endif
|
||||
|
||||
// @section more
|
||||
|
||||
//The ASCII buffer for receiving from the serial:
|
||||
#define MAX_CMD_SIZE 96
|
||||
#define BUFSIZE 4
|
||||
|
||||
// @section extras
|
||||
|
||||
// Firmware based and LCD controlled retract
|
||||
// M207 and M208 can be used to define parameters for the retraction.
|
||||
// The retraction can be called by the slicer using G10 and G11
|
||||
// until then, intended retractions can be detected by moves that only extrude and the direction.
|
||||
// the moves are than replaced by the firmware controlled ones.
|
||||
|
||||
// #define FWRETRACT //ONLY PARTIALLY TESTED
|
||||
#ifdef FWRETRACT
|
||||
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
|
||||
#define RETRACT_LENGTH 3 //default retract length (positive mm)
|
||||
#define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change
|
||||
#define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s)
|
||||
#define RETRACT_ZLIFT 0 //default retract Z-lift
|
||||
#define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering)
|
||||
#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change)
|
||||
#define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s)
|
||||
#endif
|
||||
|
||||
//adds support for experimental filament exchange support M600; requires display
|
||||
#ifdef ULTIPANEL
|
||||
#define FILAMENTCHANGEENABLE
|
||||
#ifdef FILAMENTCHANGEENABLE
|
||||
#define FILAMENTCHANGE_XPOS 3
|
||||
#define FILAMENTCHANGE_YPOS 3
|
||||
#define FILAMENTCHANGE_ZADD 10
|
||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||
#define FILAMENTCHANGE_FINALRETRACT -100
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef FILAMENTCHANGEENABLE
|
||||
#ifdef EXTRUDER_RUNOUT_PREVENT
|
||||
#error EXTRUDER_RUNOUT_PREVENT currently incompatible with FILAMENTCHANGE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//===========================================================================
|
||||
//============================= Define Defines ============================
|
||||
//===========================================================================
|
||||
|
||||
// @section hidden
|
||||
|
||||
#if defined (ENABLE_AUTO_BED_LEVELING) && defined (DELTA)
|
||||
#error "Bed Auto Leveling is still not compatible with Delta Kinematics."
|
||||
#endif
|
||||
|
||||
#if EXTRUDERS > 1 && defined TEMP_SENSOR_1_AS_REDUNDANT
|
||||
#error "You cannot use TEMP_SENSOR_1_AS_REDUNDANT if EXTRUDERS > 1"
|
||||
#endif
|
||||
|
||||
#if EXTRUDERS > 1 && defined HEATERS_PARALLEL
|
||||
#error "You cannot use HEATERS_PARALLEL if EXTRUDERS > 1"
|
||||
#endif
|
||||
|
||||
#if TEMP_SENSOR_0 > 0
|
||||
#define THERMISTORHEATER_0 TEMP_SENSOR_0
|
||||
#define HEATER_0_USES_THERMISTOR
|
||||
#endif
|
||||
#if TEMP_SENSOR_1 > 0
|
||||
#define THERMISTORHEATER_1 TEMP_SENSOR_1
|
||||
#define HEATER_1_USES_THERMISTOR
|
||||
#endif
|
||||
#if TEMP_SENSOR_2 > 0
|
||||
#define THERMISTORHEATER_2 TEMP_SENSOR_2
|
||||
#define HEATER_2_USES_THERMISTOR
|
||||
#endif
|
||||
#if TEMP_SENSOR_3 > 0
|
||||
#define THERMISTORHEATER_3 TEMP_SENSOR_3
|
||||
#define HEATER_3_USES_THERMISTOR
|
||||
#endif
|
||||
#if TEMP_SENSOR_BED > 0
|
||||
#define THERMISTORBED TEMP_SENSOR_BED
|
||||
#define BED_USES_THERMISTOR
|
||||
#endif
|
||||
#if TEMP_SENSOR_0 == -1
|
||||
#define HEATER_0_USES_AD595
|
||||
#endif
|
||||
#if TEMP_SENSOR_1 == -1
|
||||
#define HEATER_1_USES_AD595
|
||||
#endif
|
||||
#if TEMP_SENSOR_2 == -1
|
||||
#define HEATER_2_USES_AD595
|
||||
#endif
|
||||
#if TEMP_SENSOR_3 == -1
|
||||
#define HEATER_3_USES_AD595
|
||||
#endif
|
||||
#if TEMP_SENSOR_BED == -1
|
||||
#define BED_USES_AD595
|
||||
#endif
|
||||
#if TEMP_SENSOR_0 == -2
|
||||
#define HEATER_0_USES_MAX6675
|
||||
#endif
|
||||
#if TEMP_SENSOR_0 == 0
|
||||
#undef HEATER_0_MINTEMP
|
||||
#undef HEATER_0_MAXTEMP
|
||||
#endif
|
||||
#if TEMP_SENSOR_1 == 0
|
||||
#undef HEATER_1_MINTEMP
|
||||
#undef HEATER_1_MAXTEMP
|
||||
#endif
|
||||
#if TEMP_SENSOR_2 == 0
|
||||
#undef HEATER_2_MINTEMP
|
||||
#undef HEATER_2_MAXTEMP
|
||||
#endif
|
||||
#if TEMP_SENSOR_3 == 0
|
||||
#undef HEATER_3_MINTEMP
|
||||
#undef HEATER_3_MAXTEMP
|
||||
#endif
|
||||
#if TEMP_SENSOR_BED == 0
|
||||
#undef BED_MINTEMP
|
||||
#undef BED_MAXTEMP
|
||||
#endif
|
||||
|
||||
|
||||
#endif //__CONFIGURATION_ADV_H
|
1
Marlin/configurator/config/_htaccess
Normal file
|
@ -0,0 +1 @@
|
|||
Header set Access-Control-Allow-Origin "*"
|
59
Marlin/configurator/config/boards.h
Normal file
|
@ -0,0 +1,59 @@
|
|||
#ifndef BOARDS_H
|
||||
#define BOARDS_H
|
||||
|
||||
#define BOARD_UNKNOWN -1
|
||||
|
||||
#define BOARD_GEN7_CUSTOM 10 // Gen7 custom (Alfons3 Version) "https://github.com/Alfons3/Generation_7_Electronics"
|
||||
#define BOARD_GEN7_12 11 // Gen7 v1.1, v1.2
|
||||
#define BOARD_GEN7_13 12 // Gen7 v1.3
|
||||
#define BOARD_GEN7_14 13 // Gen7 v1.4
|
||||
#define BOARD_CHEAPTRONIC 2 // Cheaptronic v1.0
|
||||
#define BOARD_SETHI 20 // Sethi 3D_1
|
||||
#define BOARD_RAMPS_OLD 3 // MEGA/RAMPS up to 1.2
|
||||
#define BOARD_RAMPS_13_EFB 33 // RAMPS 1.3 / 1.4 (Extruder, Fan, Bed)
|
||||
#define BOARD_RAMPS_13_EEB 34 // RAMPS 1.3 / 1.4 (Extruder0, Extruder1, Bed)
|
||||
#define BOARD_RAMPS_13_EFF 35 // RAMPS 1.3 / 1.4 (Extruder, Fan, Fan)
|
||||
#define BOARD_RAMPS_13_EEF 36 // RAMPS 1.3 / 1.4 (Extruder0, Extruder1, Fan)
|
||||
#define BOARD_DUEMILANOVE_328P 4 // Duemilanove w/ ATMega328P pin assignments
|
||||
#define BOARD_GEN6 5 // Gen6
|
||||
#define BOARD_GEN6_DELUXE 51 // Gen6 deluxe
|
||||
#define BOARD_SANGUINOLOLU_11 6 // Sanguinololu < 1.2
|
||||
#define BOARD_SANGUINOLOLU_12 62 // Sanguinololu 1.2 and above
|
||||
#define BOARD_MELZI 63 // Melzi
|
||||
#define BOARD_STB_11 64 // STB V1.1
|
||||
#define BOARD_AZTEEG_X1 65 // Azteeg X1
|
||||
#define BOARD_MELZI_1284 66 // Melzi with ATmega1284 (MaKr3d version)
|
||||
#define BOARD_AZTEEG_X3 67 // Azteeg X3
|
||||
#define BOARD_AZTEEG_X3_PRO 68 // Azteeg X3 Pro
|
||||
#define BOARD_ULTIMAKER 7 // Ultimaker
|
||||
#define BOARD_ULTIMAKER_OLD 71 // Ultimaker (Older electronics. Pre 1.5.4. This is rare)
|
||||
#define BOARD_ULTIMAIN_2 72 // Ultimainboard 2.x (Uses TEMP_SENSOR 20)
|
||||
#define BOARD_3DRAG 77 // 3Drag
|
||||
#define BOARD_K8200 78 // Vellemann K8200 (derived from 3Drag)
|
||||
#define BOARD_TEENSYLU 8 // Teensylu
|
||||
#define BOARD_RUMBA 80 // Rumba
|
||||
#define BOARD_PRINTRBOARD 81 // Printrboard (AT90USB1286)
|
||||
#define BOARD_BRAINWAVE 82 // Brainwave (AT90USB646)
|
||||
#define BOARD_SAV_MKI 83 // SAV Mk-I (AT90USB1286)
|
||||
#define BOARD_TEENSY2 84 // Teensy++2.0 (AT90USB1286) - CLI compile: DEFINES=AT90USBxx_TEENSYPP_ASSIGNMENTS HARDWARE_MOTHERBOARD=84 make
|
||||
#define BOARD_GEN3_PLUS 9 // Gen3+
|
||||
#define BOARD_GEN3_MONOLITHIC 22 // Gen3 Monolithic Electronics
|
||||
#define BOARD_MEGATRONICS 70 // Megatronics
|
||||
#define BOARD_MEGATRONICS_2 701 // Megatronics v2.0
|
||||
#define BOARD_MEGATRONICS_1 702 // Minitronics v1.0
|
||||
#define BOARD_MEGATRONICS_3 703 // Megatronics v3.0
|
||||
#define BOARD_OMCA_A 90 // Alpha OMCA board
|
||||
#define BOARD_OMCA 91 // Final OMCA board
|
||||
#define BOARD_RAMBO 301 // Rambo
|
||||
#define BOARD_ELEFU_3 21 // Elefu Ra Board (v3)
|
||||
#define BOARD_5DPRINT 88 // 5DPrint D8 Driver Board
|
||||
#define BOARD_LEAPFROG 999 // Leapfrog
|
||||
#define BOARD_WITBOX 41 // bq WITBOX
|
||||
#define BOARD_HEPHESTOS 42 // bq Prusa i3 Hephestos
|
||||
|
||||
#define BOARD_99 99 // This is in pins.h but...?
|
||||
|
||||
#define MB(board) (MOTHERBOARD==BOARD_##board)
|
||||
#define IS_RAMPS (MB(RAMPS_OLD) || MB(RAMPS_13_EFB) || MB(RAMPS_13_EEB) || MB(RAMPS_13_EFF) || MB(RAMPS_13_EEF))
|
||||
|
||||
#endif //__BOARDS_H
|
228
Marlin/configurator/config/language.h
Normal file
|
@ -0,0 +1,228 @@
|
|||
#ifndef LANGUAGE_H
|
||||
#define LANGUAGE_H
|
||||
|
||||
#include "Configuration.h"
|
||||
|
||||
#define LANGUAGE_CONCAT(M) #M
|
||||
#define GENERATE_LANGUAGE_INCLUDE(M) LANGUAGE_CONCAT(language_##M.h)
|
||||
|
||||
|
||||
// NOTE: IF YOU CHANGE LANGUAGE FILES OR MERGE A FILE WITH CHANGES
|
||||
//
|
||||
// ==> ALWAYS TRY TO COMPILE MARLIN WITH/WITHOUT "ULTIPANEL" / "ULTRALCD" / "SDSUPPORT" #define IN "Configuration.h"
|
||||
// ==> ALSO TRY ALL AVAILABLE LANGUAGE OPTIONS
|
||||
|
||||
// Languages
|
||||
// en English
|
||||
// pl Polish
|
||||
// fr French
|
||||
// de German
|
||||
// es Spanish
|
||||
// ru Russian
|
||||
// it Italian
|
||||
// pt Portuguese
|
||||
// pt-br Portuguese (Brazil)
|
||||
// fi Finnish
|
||||
// an Aragonese
|
||||
// nl Dutch
|
||||
// ca Catalan
|
||||
// eu Basque-Euskera
|
||||
|
||||
#ifndef LANGUAGE_INCLUDE
|
||||
// pick your language from the list above
|
||||
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||
#endif
|
||||
|
||||
#define PROTOCOL_VERSION "1.0"
|
||||
#define FIRMWARE_URL "https://github.com/MarlinFirmware/Marlin"
|
||||
|
||||
#if MB(ULTIMAKER)|| MB(ULTIMAKER_OLD)|| MB(ULTIMAIN_2)
|
||||
#define MACHINE_NAME "Ultimaker"
|
||||
#define FIRMWARE_URL "http://firmware.ultimaker.com"
|
||||
#elif MB(RUMBA)
|
||||
#define MACHINE_NAME "Rumba"
|
||||
#elif MB(3DRAG)
|
||||
#define MACHINE_NAME "3Drag"
|
||||
#define FIRMWARE_URL "http://3dprint.elettronicain.it/"
|
||||
#elif MB(K8200)
|
||||
#define MACHINE_NAME "K8200"
|
||||
#elif MB(5DPRINT)
|
||||
#define MACHINE_NAME "Makibox"
|
||||
#elif MB(SAV_MKI)
|
||||
#define MACHINE_NAME "SAV MkI"
|
||||
#define FIRMWARE_URL "https://github.com/fmalpartida/Marlin/tree/SAV-MkI-config"
|
||||
#elif MB(WITBOX)
|
||||
#define MACHINE_NAME "WITBOX"
|
||||
#define FIRMWARE_URL "http://www.bq.com/gb/downloads-witbox.html"
|
||||
#elif MB(HEPHESTOS)
|
||||
#define MACHINE_NAME "HEPHESTOS"
|
||||
#define FIRMWARE_URL "http://www.bq.com/gb/downloads-prusa-i3-hephestos.html"
|
||||
#else // Default firmware set to Mendel
|
||||
#define MACHINE_NAME "Mendel"
|
||||
#endif
|
||||
|
||||
#ifdef CUSTOM_MENDEL_NAME
|
||||
#define MACHINE_NAME CUSTOM_MENDEL_NAME
|
||||
#endif
|
||||
|
||||
#ifndef MACHINE_UUID
|
||||
#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
||||
#endif
|
||||
|
||||
|
||||
#define STRINGIFY_(n) #n
|
||||
#define STRINGIFY(n) STRINGIFY_(n)
|
||||
|
||||
|
||||
// Common LCD messages
|
||||
|
||||
/* nothing here yet */
|
||||
|
||||
// Common serial messages
|
||||
#define MSG_MARLIN "Marlin"
|
||||
|
||||
// Serial Console Messages (do not translate those!)
|
||||
|
||||
#define MSG_Enqueing "enqueing \""
|
||||
#define MSG_POWERUP "PowerUp"
|
||||
#define MSG_EXTERNAL_RESET " External Reset"
|
||||
#define MSG_BROWNOUT_RESET " Brown out Reset"
|
||||
#define MSG_WATCHDOG_RESET " Watchdog Reset"
|
||||
#define MSG_SOFTWARE_RESET " Software Reset"
|
||||
#define MSG_AUTHOR " | Author: "
|
||||
#define MSG_CONFIGURATION_VER " Last Updated: "
|
||||
#define MSG_FREE_MEMORY " Free Memory: "
|
||||
#define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
#define MSG_OK "ok"
|
||||
#define MSG_FILE_SAVED "Done saving file."
|
||||
#define MSG_ERR_LINE_NO "Line Number is not Last Line Number+1, Last Line: "
|
||||
#define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
#define MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM "No Line Number with checksum, Last Line: "
|
||||
#define MSG_FILE_PRINTED "Done printing file"
|
||||
#define MSG_BEGIN_FILE_LIST "Begin file list"
|
||||
#define MSG_END_FILE_LIST "End file list"
|
||||
#define MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
|
||||
#define MSG_M105_INVALID_EXTRUDER "M105 Invalid extruder "
|
||||
#define MSG_M200_INVALID_EXTRUDER "M200 Invalid extruder "
|
||||
#define MSG_M218_INVALID_EXTRUDER "M218 Invalid extruder "
|
||||
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
||||
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||
#define MSG_HEATING "Heating..."
|
||||
#define MSG_HEATING_COMPLETE "Heating done."
|
||||
#define MSG_BED_HEATING "Bed Heating."
|
||||
#define MSG_BED_DONE "Bed done."
|
||||
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||
#define MSG_COUNT_X " Count X: "
|
||||
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
#define MSG_RESEND "Resend: "
|
||||
#define MSG_UNKNOWN_COMMAND "Unknown command: \""
|
||||
#define MSG_ACTIVE_EXTRUDER "Active Extruder: "
|
||||
#define MSG_INVALID_EXTRUDER "Invalid extruder"
|
||||
#define MSG_X_MIN "x_min: "
|
||||
#define MSG_X_MAX "x_max: "
|
||||
#define MSG_Y_MIN "y_min: "
|
||||
#define MSG_Y_MAX "y_max: "
|
||||
#define MSG_Z_MIN "z_min: "
|
||||
#define MSG_Z_MAX "z_max: "
|
||||
#define MSG_M119_REPORT "Reporting endstop status"
|
||||
#define MSG_ENDSTOP_HIT "TRIGGERED"
|
||||
#define MSG_ENDSTOP_OPEN "open"
|
||||
#define MSG_HOTEND_OFFSET "Hotend offsets:"
|
||||
|
||||
#define MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir"
|
||||
#define MSG_SD_INIT_FAIL "SD init fail"
|
||||
#define MSG_SD_VOL_INIT_FAIL "volume.init failed"
|
||||
#define MSG_SD_OPENROOT_FAIL "openRoot failed"
|
||||
#define MSG_SD_CARD_OK "SD card ok"
|
||||
#define MSG_SD_WORKDIR_FAIL "workDir open failed"
|
||||
#define MSG_SD_OPEN_FILE_FAIL "open failed, File: "
|
||||
#define MSG_SD_FILE_OPENED "File opened: "
|
||||
#define MSG_SD_SIZE " Size: "
|
||||
#define MSG_SD_FILE_SELECTED "File selected"
|
||||
#define MSG_SD_WRITE_TO_FILE "Writing to file: "
|
||||
#define MSG_SD_PRINTING_BYTE "SD printing byte "
|
||||
#define MSG_SD_NOT_PRINTING "Not SD printing"
|
||||
#define MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
|
||||
#define MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir: "
|
||||
|
||||
#define MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
||||
#define MSG_ENDSTOPS_HIT "endstops hit: "
|
||||
#define MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||
#define MSG_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented"
|
||||
#define MSG_BABYSTEPPING_X "Babystepping X"
|
||||
#define MSG_BABYSTEPPING_Y "Babystepping Y"
|
||||
#define MSG_BABYSTEPPING_Z "Babystepping Z"
|
||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
|
||||
|
||||
#define MSG_ERR_EEPROM_WRITE "Error writing to EEPROM!"
|
||||
|
||||
// LCD Menu Messages
|
||||
|
||||
// Add your own character. Reference: https://github.com/MarlinFirmware/Marlin/pull/1434 photos
|
||||
// and https://www.sparkfun.com/datasheets/LCD/HD44780.pdf page 17-18
|
||||
#ifdef DOGLCD
|
||||
#define STR_Ae "\304" // 'Ä' U8glib
|
||||
#define STR_ae "\344" // 'ä'
|
||||
#define STR_Oe "\326" // 'Ö'
|
||||
#define STR_oe STR_Oe // 'ö'
|
||||
#define STR_Ue "\334" // 'Ü'
|
||||
#define STR_ue STR_Ue // 'ü'
|
||||
#define STR_sz "\337" // 'ß'
|
||||
#define STR_h2 "\262" // '²'
|
||||
#define STR_h3 "\263" // '³'
|
||||
#define STR_Deg "\260" // '°'
|
||||
#define STR_THERMOMETER "\377"
|
||||
#else
|
||||
#ifdef DISPLAY_CHARSET_HD44780_JAPAN // HD44780 ROM Code: A00 (Japan)
|
||||
#define STR_ae "\xe1"
|
||||
#define STR_Ae STR_ae
|
||||
#define STR_oe "\357"
|
||||
#define STR_Oe STR_oe
|
||||
#define STR_ue "\365"
|
||||
#define STR_Ue STR_ue
|
||||
#define STR_sz "\342"
|
||||
#define STR_h2 "2"
|
||||
#define STR_h3 "3"
|
||||
#define STR_Deg "\271"
|
||||
#define STR_THERMOMETER "\002"
|
||||
#endif
|
||||
#ifdef DISPLAY_CHARSET_HD44780_WESTERN // HD44780 ROM Code: A02 (Western)
|
||||
#define STR_Ae "\216"
|
||||
#define STR_ae "\204"
|
||||
#define STR_Oe "\211"
|
||||
#define STR_oe "\204"
|
||||
#define STR_Ue "\212"
|
||||
#define STR_ue "\201"
|
||||
#define STR_sz "\160"
|
||||
#define STR_h2 "\262"
|
||||
#define STR_h3 "\263"
|
||||
#define STR_Deg "\337"
|
||||
#define STR_THERMOMETER "\002"
|
||||
#endif
|
||||
#endif
|
||||
/*
|
||||
#define TESTSTRING000 "\000\001\002\003\004\005\006\007\010\011\012\013\014\015\016\017"
|
||||
#define TESTSTRING020 "\020\021\022\023\024\025\026\027\030\031\032\033\034\035\036\037"
|
||||
#define TESTSTRING040 "\040\041\042\043\044\045\046\047\050\051\052\053\054\055\056\057"
|
||||
#define TESTSTRING060 "\060\061\062\063\064\065\066\067\070\071\072\073\074\075\076\077"
|
||||
#define TESTSTRING100 "\100\101\102\103\104\105\106\107\110\111\112\113\114\115\116\117"
|
||||
#define TESTSTRING120 "\120\121\122\123\124\125\126\127\130\131\132\133\134\135\136\137"
|
||||
#define TESTSTRING140 "\140\141\142\143\144\145\146\147\150\151\152\153\154\155\156\157"
|
||||
#define TESTSTRING160 "\160\161\162\163\164\165\166\167\170\171\172\173\174\175\176\177"
|
||||
#define TESTSTRING200 "\200\201\202\203\204\205\206\207\210\211\212\213\214\215\216\217"
|
||||
#define TESTSTRING220 "\220\221\222\223\224\225\226\227\230\231\232\233\234\235\236\237"
|
||||
#define TESTSTRING240 "\240\241\242\243\244\245\246\247\250\251\252\253\254\255\256\257"
|
||||
#define TESTSTRING260 "\260\261\262\263\264\265\266\267\270\271\272\273\274\275\276\277"
|
||||
#define TESTSTRING300 "\300\301\302\303\304\305\306\307\310\311\312\313\314\315\316\317"
|
||||
#define TESTSTRING320 "\320\321\322\323\324\325\326\327\330\331\332\333\334\335\336\337"
|
||||
#define TESTSTRING340 "\340\341\342\343\344\345\346\347\350\351\352\353\354\355\356\357"
|
||||
#define TESTSTRING360 "\360\361\362\363\364\365\366\367\370\371\372\373\374\375\376\377"
|
||||
*/
|
||||
|
||||
#include LANGUAGE_INCLUDE
|
||||
#include "language_en.h"
|
||||
|
||||
#endif //__LANGUAGE_H
|
344
Marlin/configurator/css/configurator.css
Normal file
|
@ -0,0 +1,344 @@
|
|||
/* configurator.css */
|
||||
/* Styles for Marlin Configurator */
|
||||
|
||||
.clear { clear: both; }
|
||||
|
||||
/* Prevent selection except PRE tags */
|
||||
* {
|
||||
-webkit-touch-callout: none;
|
||||
-webkit-user-select: none;
|
||||
-khtml-user-select: none;
|
||||
-moz-user-select: none;
|
||||
-ms-user-select: none;
|
||||
user-select: none;
|
||||
}
|
||||
pre {
|
||||
-webkit-touch-callout: text;
|
||||
-webkit-user-select: text;
|
||||
-khtml-user-select: text;
|
||||
-moz-user-select: text;
|
||||
-ms-user-select: text;
|
||||
user-select: text;
|
||||
}
|
||||
|
||||
body { margin: 0; padding: 0; background: #56A; color: #000; font-family: monospace; }
|
||||
#main {
|
||||
max-width: 1100px;
|
||||
margin: 0 auto 10px;
|
||||
padding: 0 2%; width: 96%;
|
||||
}
|
||||
|
||||
h1, h2, h3, h4, h5, h6 { clear: both; }
|
||||
|
||||
h1, p.info { font-family: sans-serif; }
|
||||
h1 {
|
||||
height: 38px;
|
||||
margin-bottom: -30px;
|
||||
color: #FFF;
|
||||
background: transparent url(logo.png) right top no-repeat;
|
||||
}
|
||||
p.info { padding: 0; color: #000; }
|
||||
p.info span { color: #800; }
|
||||
|
||||
#message { text-align: center; }
|
||||
#message { width: 80%; margin: 0 auto 0.25em; color: #FF0; }
|
||||
#message p { padding: 2px 0; font-weight: bold; border-radius: 0.8em; }
|
||||
#message p.message { color: #080; background: #CFC; }
|
||||
#message p.error { color: #F00; background: #FF4; }
|
||||
#message p.warning { color: #FF0; background: #BA4; }
|
||||
#message p.message span,
|
||||
#message p.error span,
|
||||
#message p.warning span {
|
||||
color: #A00;
|
||||
background: rgba(255, 255, 255, 1);
|
||||
border: 1px solid rgba(0,0,0,0.5);
|
||||
border-radius: 1em;
|
||||
float: right;
|
||||
margin-right: 0.5em;
|
||||
padding: 0 3px;
|
||||
font-family: sans-serif;
|
||||
font-size: small;
|
||||
position: relative;
|
||||
top: -1px;
|
||||
}
|
||||
|
||||
#help strong { color: #0DD; }
|
||||
img { display: none; }
|
||||
|
||||
/* Forms */
|
||||
|
||||
#config_form {
|
||||
display: block;
|
||||
background: #EEE;
|
||||
padding: 6px 20px 20px;
|
||||
color: #000;
|
||||
position: relative;
|
||||
border-radius: 1.5em;
|
||||
border-top-left-radius: 0;
|
||||
}
|
||||
fieldset {
|
||||
height: 16.1em;
|
||||
overflow-y: scroll;
|
||||
overflow-x: hidden;
|
||||
margin-top: 10px;
|
||||
}
|
||||
label, input, select, textarea { display: block; float: left; margin: 1px 0; }
|
||||
label.newline, textarea, fieldset { clear: both; }
|
||||
label {
|
||||
width: 120px; /* label area */
|
||||
height: 1em;
|
||||
padding: 10px 460px 10px 1em;
|
||||
margin-right: -450px;
|
||||
text-align: right;
|
||||
}
|
||||
label.blocked, label.added.blocked, label.added.blocked.sublabel { color: #AAA; }
|
||||
|
||||
label.added.sublabel {
|
||||
width: auto;
|
||||
margin: 11px -2.5em 0 1em;
|
||||
padding: 0 3em 0 0;
|
||||
font-style: italic;
|
||||
color: #444;
|
||||
}
|
||||
label+label.added.sublabel {
|
||||
margin-left: 0;
|
||||
}
|
||||
|
||||
input[type="text"], select { margin: 0.75em 0 0; }
|
||||
input[type="checkbox"], input[type="radio"], input[type="file"] { margin: 1em 0 0; }
|
||||
input[type="checkbox"].enabler, input[type="radio"].enabler { margin-left: 1em; }
|
||||
|
||||
input:disabled { color: #BBB; }
|
||||
|
||||
#config_form input[type="text"].subitem { width: 4em; }
|
||||
#config_form input[type="text"].subitem+.subitem { margin-left: 4px; }
|
||||
|
||||
input[type="text"].added { width: 20em; }
|
||||
label.added {
|
||||
width: 265px; /* label area */
|
||||
height: 1em;
|
||||
padding: 10px 370px 10px 1em;
|
||||
margin-right: -360px;
|
||||
text-align: right;
|
||||
}
|
||||
|
||||
ul.tabs { padding: 0; list-style: none; }
|
||||
ul.tabs li { display: inline; }
|
||||
ul.tabs li a,
|
||||
ul.tabs li a.active:hover,
|
||||
ul.tabs li a.active:active {
|
||||
display: block;
|
||||
float: left;
|
||||
background: #1E4059;
|
||||
color: #CCC;
|
||||
font-size: 110%;
|
||||
border-radius: 0.25em 0.25em 0 0;
|
||||
margin: 0 4px 0 0;
|
||||
padding: 2px 8px;
|
||||
text-decoration: none;
|
||||
font-family: georgia,"times new roman",times;
|
||||
}
|
||||
ul.tabs li a.active:link,
|
||||
ul.tabs li a.active:visited {
|
||||
background: #DDD;
|
||||
color: #06F;
|
||||
cursor: default;
|
||||
margin-top: -4px;
|
||||
padding-bottom: 4px;
|
||||
padding-top: 4px;
|
||||
}
|
||||
ul.tabs li a:hover,
|
||||
ul.tabs li a:active {
|
||||
background: #000;
|
||||
color: #FFF;
|
||||
}
|
||||
|
||||
fieldset { display: none; border: 1px solid #AAA; border-radius: 1em; }
|
||||
fieldset legend { display: none; }
|
||||
|
||||
.hilightable span {
|
||||
display: block;
|
||||
float: left;
|
||||
width: 100%;
|
||||
height: 1.3em;
|
||||
background: rgba(225,255,0,1);
|
||||
margin: 0 -100% -1em 0;
|
||||
}
|
||||
|
||||
#serial_stepper { padding-top: 0.75em; display: block; float: left; }
|
||||
/*#SERIAL_PORT { display: none; }*/
|
||||
|
||||
/* Tooltips */
|
||||
|
||||
#tooltip {
|
||||
display: none;
|
||||
max-width: 30em;
|
||||
padding: 8px;
|
||||
border: 2px solid #73d699;
|
||||
border-radius: 1em;
|
||||
position: absolute;
|
||||
z-index: 999;
|
||||
font-family: sans-serif;
|
||||
font-size: 85%;
|
||||
color: #000;
|
||||
line-height: 1.1;
|
||||
background: #e2ff99; /* Old browsers */
|
||||
background: -moz-linear-gradient(top, #e2ff99 0%, #73d699 100%); /* FF3.6+ */
|
||||
background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#e2ff99), color-stop(100%,#73d699)); /* Chrome,Safari4+ */
|
||||
background: -webkit-linear-gradient(top, #e2ff99 0%,#73d699 100%); /* Chrome10+,Safari5.1+ */
|
||||
background: -o-linear-gradient(top, #e2ff99 0%,#73d699 100%); /* Opera 11.10+ */
|
||||
background: -ms-linear-gradient(top, #e2ff99 0%,#73d699 100%); /* IE10+ */
|
||||
background: linear-gradient(to bottom, #e2ff99 0%,#73d699 100%); /* W3C */
|
||||
filter: progid:DXImageTransform.Microsoft.gradient( startColorstr='#e2ff99', endColorstr='#73d699',GradientType=0 ); /* IE6-9 */
|
||||
-webkit-box-shadow: 0px 6px 25px -4px rgba(0,0,0,0.75);
|
||||
-moz-box-shadow: 0px 6px 25px -4px rgba(0,0,0,0.75);
|
||||
box-shadow: 0px 6px 25px -4px rgba(0,0,0,0.75);
|
||||
}
|
||||
#tooltip>span {
|
||||
position: absolute;
|
||||
content: "";
|
||||
width: 0;
|
||||
height: 0;
|
||||
border-left: 8px solid transparent;
|
||||
border-right: 8px solid transparent;
|
||||
border-top: 8px solid #73d699;
|
||||
z-index: 999;
|
||||
bottom: -10px;
|
||||
left: 20px;
|
||||
}
|
||||
#tooltip>strong { color: #00B; }
|
||||
|
||||
/* Tooltips Checkbox */
|
||||
|
||||
#tipson {
|
||||
width: auto;
|
||||
height: auto;
|
||||
padding: 0;
|
||||
margin-right: 0;
|
||||
float: right;
|
||||
font-weight: bold;
|
||||
font-size: 100%;
|
||||
font-family: helvetica;
|
||||
text-align: left;
|
||||
cursor: pointer;
|
||||
}
|
||||
#tipson input { float: none; display: inline; cursor: pointer; }
|
||||
|
||||
/* Config Text */
|
||||
|
||||
pre.config {
|
||||
height: 25em;
|
||||
padding: 10px;
|
||||
border: 2px solid #888;
|
||||
border-radius: 5px;
|
||||
overflow: auto;
|
||||
clear: both;
|
||||
background-color: #FFF;
|
||||
color: #000;
|
||||
font-family: "Fira Mono", monospace;
|
||||
font-size: small;
|
||||
}
|
||||
|
||||
/* Pre Headers */
|
||||
|
||||
h2 {
|
||||
width: 100%;
|
||||
margin: 12px -300px 4px 0;
|
||||
padding: 0;
|
||||
float: left;
|
||||
}
|
||||
|
||||
/* Disclosure Widget */
|
||||
|
||||
span.disclose, a.download, a.download-all {︎
|
||||
display: block;
|
||||
float: right;
|
||||
margin-top: 12px;
|
||||
}
|
||||
|
||||
span.disclose {
|
||||
margin-right: -10px; /* total width */
|
||||
margin-left: 14px;
|
||||
width: 0;
|
||||
height: 0;
|
||||
position: relative;
|
||||
left: 3px;
|
||||
top: 3px;
|
||||
cursor: pointer;
|
||||
border-left: 8px solid transparent;
|
||||
border-right: 8px solid transparent;
|
||||
border-top: 10px solid #000;
|
||||
}
|
||||
span.disclose.closed {
|
||||
margin-right: -8px; /* total width */
|
||||
margin-left: 10px;
|
||||
left: 0;
|
||||
top: 0;
|
||||
border-top: 8px solid transparent;
|
||||
border-bottom: 8px solid transparent;
|
||||
border-right: 10px solid #000;
|
||||
}
|
||||
span.disclose.almost {
|
||||
-ms-transform: rotate(45deg); /* IE 9 */
|
||||
-webkit-transform: rotate(45deg); /* Chrome, Safari, Opera */
|
||||
transform: rotate(45deg);
|
||||
}
|
||||
span.disclose.closed.almost {
|
||||
left: 1px;
|
||||
top: 3px;
|
||||
-ms-transform: rotate(315deg); /* IE 9 */
|
||||
-webkit-transform: rotate(315deg); /* Chrome, Safari, Opera */
|
||||
transform: rotate(315deg);
|
||||
}
|
||||
|
||||
/* Download Button */
|
||||
|
||||
a.download, a.download-all {
|
||||
visibility: hidden;
|
||||
padding: 2px;
|
||||
border: 1px solid #494;
|
||||
border-radius: 4px;
|
||||
margin: 12px 0 0;
|
||||
background: #FFF;
|
||||
color: #494;
|
||||
font-family: sans-serif;
|
||||
font-size: small;
|
||||
font-weight: bold;
|
||||
text-decoration: none;
|
||||
}
|
||||
a.download-all { margin: 9px 2em 0; color: #449; border-color: #449; }
|
||||
|
||||
input[type="text"].one_of_2 { max-width: 15%; }
|
||||
input[type="text"].one_of_3 { max-width: 10%; }
|
||||
input[type="text"].one_of_4 { max-width: 7%; }
|
||||
|
||||
select.one_of_2 { max-width: 15%; }
|
||||
select.one_of_3 { max-width: 10%; }
|
||||
select.one_of_4 { max-width: 14%; }
|
||||
select.one_of_4+span.label+select.one_of_4+span.label { clear: both; margin-left: 265px; padding-left: 1.75em; }
|
||||
select.one_of_4+span.label+select.one_of_4+span.label+select.one_of_4+span.label { clear: none; margin-left: 1em; padding-left: 0; }
|
||||
|
||||
@media all and (min-width: 1140px) {
|
||||
|
||||
#main { max-width: 10000px; }
|
||||
|
||||
fieldset { float: left; width: 50%; height: auto; }
|
||||
|
||||
#config_text, #config_adv_text { float: right; clear: right; width: 45%; }
|
||||
|
||||
pre.config { height: 20em; }
|
||||
|
||||
.disclose { display: none; }
|
||||
|
||||
input[type="text"].one_of_2 { max-width: 15%; }
|
||||
input[type="text"].one_of_3 { max-width: 9%; }
|
||||
input[type="text"].one_of_4 { max-width: 8%; }
|
||||
|
||||
select.one_of_2 { max-width: 15%; }
|
||||
select.one_of_3 { max-width: 10%; }
|
||||
select.one_of_4 { max-width: 16%; }
|
||||
|
||||
}
|
||||
|
||||
/*label.blocked, .blocked { display: none; }*/
|
||||
|
BIN
Marlin/configurator/css/logo.png
Normal file
After Width: | Height: | Size: 1.2 KiB |
117
Marlin/configurator/index.html
Normal file
|
@ -0,0 +1,117 @@
|
|||
<!DOCTYPE html>
|
||||
<html>
|
||||
<head>
|
||||
<meta charset="UTF-8">
|
||||
<title>Marlin Firmware Configurator</title>
|
||||
<link href='http://fonts.googleapis.com/css?family=Fira+Mono&subset=latin,latin-ext' rel='stylesheet' type='text/css' />
|
||||
<script src="js/jquery-2.1.3.min.js"></script>
|
||||
<script src="js/binarystring.js"></script>
|
||||
<script src="js/binaryfileuploader.js"></script>
|
||||
<script src="js/FileSaver.min.js"></script>
|
||||
<script src="js/jszip.min.js"></script>
|
||||
<script src="js/jcanvas.js"></script>
|
||||
<script src="js/jstepper.js"></script>
|
||||
<script src="js/configurator.js"></script>
|
||||
<link rel="stylesheet" href="css/configurator.css" type="text/css" media="all" />
|
||||
</head>
|
||||
<body>
|
||||
<section id="main">
|
||||
<h1>Marlin Configurator</h1>
|
||||
<p class="info">Select presets (coming soon), modify, and download.</p>
|
||||
|
||||
<div id="message"></div>
|
||||
<div id="tabs"></div>
|
||||
|
||||
<form id="config_form">
|
||||
|
||||
<div id="tooltip"></div>
|
||||
|
||||
<label>Drop Files:</label><input type="file" id="file-upload" />
|
||||
<label id="tipson"><input type="checkbox" checked /> ?</label>
|
||||
<a href="" class="download-all">Download Zip</a>
|
||||
|
||||
<fieldset id="machine">
|
||||
<legend>Machine</legend>
|
||||
|
||||
<label class="newline">Serial Port:</label><select name="SERIAL_PORT"></select><div id="serial_stepper"></div>
|
||||
|
||||
<label>Baud Rate:</label><select name="BAUDRATE"></select>
|
||||
|
||||
<label>AT90USB BT IF:</label>
|
||||
<input name="BTENABLED" type="checkbox" value="1" checked />
|
||||
|
||||
<label class="newline">Motherboard:</label><select name="MOTHERBOARD"></select>
|
||||
|
||||
<label class="newline">Custom Name:</label><input name="CUSTOM_MENDEL_NAME" type="text" size="14" maxlength="12" value="" />
|
||||
|
||||
<label class="newline">Machine UUID:</label><input name="MACHINE_UUID" type="text" size="38" maxlength="36" value="" />
|
||||
|
||||
<label class="newline">Extruders:</label><select name="EXTRUDERS"></select>
|
||||
|
||||
<label class="newline">Power Supply:</label><select name="POWER_SUPPLY"></select>
|
||||
|
||||
<label>PS Default Off:</label>
|
||||
<input name="PS_DEFAULT_OFF" type="checkbox" value="1" checked />
|
||||
</fieldset>
|
||||
|
||||
<fieldset id="homing">
|
||||
<legend>Homing</legend>
|
||||
</fieldset>
|
||||
|
||||
<fieldset id="temperature">
|
||||
<legend>Temperature</legend>
|
||||
<label class="newline">Temp Sensor 0:</label><select name="TEMP_SENSOR_0"></select>
|
||||
<label class="newline">Temp Sensor 1:</label><select name="TEMP_SENSOR_1"></select>
|
||||
<label class="newline">Temp Sensor 2:</label><select name="TEMP_SENSOR_2"></select>
|
||||
<label class="newline">Bed Temp Sensor:</label><select name="TEMP_SENSOR_BED"></select>
|
||||
|
||||
<label>Max Diff:</label>
|
||||
<input name="MAX_REDUNDANT_TEMP_SENSOR_DIFF" type="text" size="3" maxlength="2" />
|
||||
|
||||
<label>Temp Residency Time (s):</label>
|
||||
<input name="TEMP_RESIDENCY_TIME" type="text" size="3" maxlength="2" />
|
||||
</fieldset>
|
||||
|
||||
<fieldset id="extruder">
|
||||
<legend>Extruder</legend>
|
||||
</fieldset>
|
||||
|
||||
<fieldset id="lcd">
|
||||
<legend>LCD / SD</legend>
|
||||
</fieldset>
|
||||
|
||||
<fieldset id="bedlevel">
|
||||
<legend>Bed Leveling</legend>
|
||||
</fieldset>
|
||||
|
||||
<fieldset id="extras">
|
||||
<legend>Extras</legend>
|
||||
</fieldset>
|
||||
|
||||
<fieldset id="info">
|
||||
<legend>Info</legend>
|
||||
</fieldset>
|
||||
|
||||
<fieldset id="more">
|
||||
<legend>More…</legend>
|
||||
</fieldset>
|
||||
|
||||
<section id="config_text">
|
||||
<h2>Configuration.h</h2>
|
||||
<span class="disclose"></span>
|
||||
<a href="" class="download">Download</a>
|
||||
<pre class="hilightable config"></pre>
|
||||
</section>
|
||||
|
||||
<section id="config_adv_text">
|
||||
<h2>Configuration_adv.h</h2>
|
||||
<span class="disclose"></span>
|
||||
<a href="" class="download">Download</a>
|
||||
<pre class="hilightable config"></pre>
|
||||
</section>
|
||||
|
||||
<br class="clear" />
|
||||
</form>
|
||||
</section>
|
||||
</body>
|
||||
</html>
|
2
Marlin/configurator/js/FileSaver.min.js
vendored
Executable file
|
@ -0,0 +1,2 @@
|
|||
/*! @source http://purl.eligrey.com/github/FileSaver.js/blob/master/FileSaver.js */
|
||||
var saveAs=saveAs||typeof navigator!=="undefined"&&navigator.msSaveOrOpenBlob&&navigator.msSaveOrOpenBlob.bind(navigator)||function(view){"use strict";if(typeof navigator!=="undefined"&&/MSIE [1-9]\./.test(navigator.userAgent)){return}var doc=view.document,get_URL=function(){return view.URL||view.webkitURL||view},save_link=doc.createElementNS("http://www.w3.org/1999/xhtml","a"),can_use_save_link="download"in save_link,click=function(node){var event=doc.createEvent("MouseEvents");event.initMouseEvent("click",true,false,view,0,0,0,0,0,false,false,false,false,0,null);node.dispatchEvent(event)},webkit_req_fs=view.webkitRequestFileSystem,req_fs=view.requestFileSystem||webkit_req_fs||view.mozRequestFileSystem,throw_outside=function(ex){(view.setImmediate||view.setTimeout)(function(){throw ex},0)},force_saveable_type="application/octet-stream",fs_min_size=0,arbitrary_revoke_timeout=500,revoke=function(file){var revoker=function(){if(typeof file==="string"){get_URL().revokeObjectURL(file)}else{file.remove()}};if(view.chrome){revoker()}else{setTimeout(revoker,arbitrary_revoke_timeout)}},dispatch=function(filesaver,event_types,event){event_types=[].concat(event_types);var i=event_types.length;while(i--){var listener=filesaver["on"+event_types[i]];if(typeof listener==="function"){try{listener.call(filesaver,event||filesaver)}catch(ex){throw_outside(ex)}}}},FileSaver=function(blob,name){var filesaver=this,type=blob.type,blob_changed=false,object_url,target_view,dispatch_all=function(){dispatch(filesaver,"writestart progress write writeend".split(" "))},fs_error=function(){if(blob_changed||!object_url){object_url=get_URL().createObjectURL(blob)}if(target_view){target_view.location.href=object_url}else{var new_tab=view.open(object_url,"_blank");if(new_tab==undefined&&typeof safari!=="undefined"){view.location.href=object_url}}filesaver.readyState=filesaver.DONE;dispatch_all();revoke(object_url)},abortable=function(func){return function(){if(filesaver.readyState!==filesaver.DONE){return func.apply(this,arguments)}}},create_if_not_found={create:true,exclusive:false},slice;filesaver.readyState=filesaver.INIT;if(!name){name="download"}if(can_use_save_link){object_url=get_URL().createObjectURL(blob);save_link.href=object_url;save_link.download=name;click(save_link);filesaver.readyState=filesaver.DONE;dispatch_all();revoke(object_url);return}if(view.chrome&&type&&type!==force_saveable_type){slice=blob.slice||blob.webkitSlice;blob=slice.call(blob,0,blob.size,force_saveable_type);blob_changed=true}if(webkit_req_fs&&name!=="download"){name+=".download"}if(type===force_saveable_type||webkit_req_fs){target_view=view}if(!req_fs){fs_error();return}fs_min_size+=blob.size;req_fs(view.TEMPORARY,fs_min_size,abortable(function(fs){fs.root.getDirectory("saved",create_if_not_found,abortable(function(dir){var save=function(){dir.getFile(name,create_if_not_found,abortable(function(file){file.createWriter(abortable(function(writer){writer.onwriteend=function(event){target_view.location.href=file.toURL();filesaver.readyState=filesaver.DONE;dispatch(filesaver,"writeend",event);revoke(file)};writer.onerror=function(){var error=writer.error;if(error.code!==error.ABORT_ERR){fs_error()}};"writestart progress write abort".split(" ").forEach(function(event){writer["on"+event]=filesaver["on"+event]});writer.write(blob);filesaver.abort=function(){writer.abort();filesaver.readyState=filesaver.DONE};filesaver.readyState=filesaver.WRITING}),fs_error)}),fs_error)};dir.getFile(name,{create:false},abortable(function(file){file.remove();save()}),abortable(function(ex){if(ex.code===ex.NOT_FOUND_ERR){save()}else{fs_error()}}))}),fs_error)}),fs_error)},FS_proto=FileSaver.prototype,saveAs=function(blob,name){return new FileSaver(blob,name)};FS_proto.abort=function(){var filesaver=this;filesaver.readyState=filesaver.DONE;dispatch(filesaver,"abort")};FS_proto.readyState=FS_proto.INIT=0;FS_proto.WRITING=1;FS_proto.DONE=2;FS_proto.error=FS_proto.onwritestart=FS_proto.onprogress=FS_proto.onwrite=FS_proto.onabort=FS_proto.onerror=FS_proto.onwriteend=null;return saveAs}(typeof self!=="undefined"&&self||typeof window!=="undefined"&&window||this.content);if(typeof module!=="undefined"&&module.exports){module.exports.saveAs=saveAs}else if(typeof define!=="undefined"&&define!==null&&define.amd!=null){define([],function(){return saveAs})}
|
79
Marlin/configurator/js/binaryfileuploader.js
Normal file
|
@ -0,0 +1,79 @@
|
|||
function BinaryFileUploader(o) {
|
||||
this.options = null;
|
||||
|
||||
|
||||
this._defaultOptions = {
|
||||
element: null, // HTML file element
|
||||
onFileLoad: function(file) {
|
||||
console.log(file.toString());
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
this._init = function(o) {
|
||||
if (!this.hasFileUploaderSupport()) return;
|
||||
|
||||
this._verifyDependencies();
|
||||
|
||||
this.options = this._mergeObjects(this._defaultOptions, o);
|
||||
this._verifyOptions();
|
||||
|
||||
this.addFileChangeListener();
|
||||
}
|
||||
|
||||
|
||||
this.hasFileUploaderSupport = function() {
|
||||
return !!(window.File && window.FileReader && window.FileList && window.Blob);
|
||||
}
|
||||
|
||||
this.addFileChangeListener = function() {
|
||||
this.options.element.addEventListener(
|
||||
'change',
|
||||
this._bind(this, this.onFileChange)
|
||||
);
|
||||
}
|
||||
|
||||
this.onFileChange = function(e) {
|
||||
// TODO accept multiple files
|
||||
var file = e.target.files[0],
|
||||
reader = new FileReader();
|
||||
|
||||
reader.onload = this._bind(this, this.onFileLoad);
|
||||
reader.readAsBinaryString(file);
|
||||
}
|
||||
|
||||
this.onFileLoad = function(e) {
|
||||
var content = e.target.result,
|
||||
string = new BinaryString(content);
|
||||
this.options.onFileLoad(string);
|
||||
}
|
||||
|
||||
|
||||
this._mergeObjects = function(starting, override) {
|
||||
var merged = starting;
|
||||
for (key in override) merged[key] = override[key];
|
||||
|
||||
return merged;
|
||||
}
|
||||
|
||||
this._verifyOptions = function() {
|
||||
if (!(this.options.element && this.options.element.type && this.options.element.type === 'file')) {
|
||||
throw 'Invalid element param in options. Must be a file upload DOM element';
|
||||
}
|
||||
|
||||
if (typeof this.options.onFileLoad !== 'function') {
|
||||
throw 'Invalid onFileLoad param in options. Must be a function';
|
||||
}
|
||||
}
|
||||
|
||||
this._verifyDependencies = function() {
|
||||
if (!window.BinaryString) throw 'BinaryString is missing. Check that you\'ve correctly included it';
|
||||
}
|
||||
|
||||
// helper function for binding methods to objects
|
||||
this._bind = function(object, method) {
|
||||
return function() {return method.apply(object, arguments);};
|
||||
}
|
||||
|
||||
this._init(o);
|
||||
}
|
168
Marlin/configurator/js/binarystring.js
Normal file
|
@ -0,0 +1,168 @@
|
|||
function BinaryString(source) {
|
||||
this._source = null;
|
||||
this._bytes = [];
|
||||
this._pos = 0;
|
||||
this._length = 0;
|
||||
|
||||
this._init = function(source) {
|
||||
this._source = source;
|
||||
this._bytes = this._stringToBytes(this._source);
|
||||
this._length = this._bytes.length;
|
||||
}
|
||||
|
||||
this.current = function() {return this._pos;}
|
||||
|
||||
this.rewind = function() {return this.jump(0);}
|
||||
this.end = function() {return this.jump(this.length() - 1);}
|
||||
this.next = function() {return this.jump(this.current() + 1);}
|
||||
this.prev = function() {return this.jump(this.current() - 1);}
|
||||
|
||||
this.jump = function(pos) {
|
||||
if (pos < 0 || pos >= this.length()) return false;
|
||||
|
||||
this._pos = pos;
|
||||
return true;
|
||||
}
|
||||
|
||||
this.readByte = function(pos) {
|
||||
pos = (typeof pos == 'number') ? pos : this.current();
|
||||
return this.readBytes(1, pos)[0];
|
||||
}
|
||||
|
||||
this.readBytes = function(length, pos) {
|
||||
length = length || 1;
|
||||
pos = (typeof pos == 'number') ? pos : this.current();
|
||||
|
||||
if (pos > this.length() ||
|
||||
pos < 0 ||
|
||||
length <= 0 ||
|
||||
pos + length > this.length() ||
|
||||
pos + length < 0
|
||||
) {
|
||||
return false;
|
||||
}
|
||||
|
||||
var bytes = [];
|
||||
|
||||
for (var i = pos; i < pos + length; i++) {
|
||||
bytes.push(this._bytes[i]);
|
||||
}
|
||||
|
||||
return bytes;
|
||||
}
|
||||
|
||||
this.length = function() {return this._length;}
|
||||
|
||||
this.toString = function() {
|
||||
var string = '',
|
||||
length = this.length();
|
||||
|
||||
for (var i = 0; i < length; i++) {
|
||||
string += String.fromCharCode(this.readByte(i));
|
||||
}
|
||||
|
||||
return string;
|
||||
}
|
||||
|
||||
this.toUtf8 = function() {
|
||||
var inc = 0,
|
||||
string = '',
|
||||
length = this.length();
|
||||
|
||||
// determine if first 3 characters are the BOM
|
||||
// then skip them in output if so
|
||||
if (length >= 3 &&
|
||||
this.readByte(0) === 0xEF &&
|
||||
this.readByte(1) === 0xBB &&
|
||||
this.readByte(2) === 0xBF
|
||||
) {
|
||||
inc = 3;
|
||||
}
|
||||
|
||||
for (; inc < length; inc++) {
|
||||
var byte1 = this.readByte(inc),
|
||||
byte2 = 0,
|
||||
byte3 = 0,
|
||||
byte4 = 0,
|
||||
code1 = 0,
|
||||
code2 = 0,
|
||||
point = 0;
|
||||
|
||||
switch (true) {
|
||||
// single byte character; same as ascii
|
||||
case (byte1 < 0x80):
|
||||
code1 = byte1;
|
||||
break;
|
||||
|
||||
// 2 byte character
|
||||
case (byte1 >= 0xC2 && byte1 < 0xE0):
|
||||
byte2 = this.readByte(++inc);
|
||||
|
||||
code1 = ((byte1 & 0x1F) << 6) +
|
||||
(byte2 & 0x3F);
|
||||
break;
|
||||
|
||||
// 3 byte character
|
||||
case (byte1 >= 0xE0 && byte1 < 0xF0):
|
||||
byte2 = this.readByte(++inc);
|
||||
byte3 = this.readByte(++inc);
|
||||
|
||||
code1 = ((byte1 & 0xFF) << 12) +
|
||||
((byte2 & 0x3F) << 6) +
|
||||
(byte3 & 0x3F);
|
||||
break;
|
||||
|
||||
// 4 byte character
|
||||
case (byte1 >= 0xF0 && byte1 < 0xF5):
|
||||
byte2 = this.readByte(++inc);
|
||||
byte3 = this.readByte(++inc);
|
||||
byte4 = this.readByte(++inc);
|
||||
|
||||
point = ((byte1 & 0x07) << 18) +
|
||||
((byte2 & 0x3F) << 12) +
|
||||
((byte3 & 0x3F) << 6) +
|
||||
(byte4 & 0x3F)
|
||||
point -= 0x10000;
|
||||
|
||||
code1 = (point >> 10) + 0xD800;
|
||||
code2 = (point & 0x3FF) + 0xDC00;
|
||||
break;
|
||||
|
||||
default:
|
||||
throw 'Invalid byte ' + this._byteToString(byte1) + ' whilst converting to UTF-8';
|
||||
break;
|
||||
}
|
||||
|
||||
string += (code2) ? String.fromCharCode(code1, code2)
|
||||
: String.fromCharCode(code1);
|
||||
}
|
||||
|
||||
return string;
|
||||
}
|
||||
|
||||
this.toArray = function() {return this.readBytes(this.length() - 1, 0);}
|
||||
|
||||
|
||||
this._stringToBytes = function(str) {
|
||||
var bytes = [],
|
||||
chr = 0;
|
||||
|
||||
for (var i = 0; i < str.length; i++) {
|
||||
chr = str.charCodeAt(i);
|
||||
bytes.push(chr & 0xFF);
|
||||
}
|
||||
|
||||
return bytes;
|
||||
}
|
||||
|
||||
this._byteToString = function(byte) {
|
||||
var asString = byte.toString(16).toUpperCase();
|
||||
while (asString.length < 2) {
|
||||
asString = '0' + asString;
|
||||
}
|
||||
|
||||
return '0x' + asString;
|
||||
}
|
||||
|
||||
this._init(source);
|
||||
}
|
1414
Marlin/configurator/js/configurator.js
Normal file
524
Marlin/configurator/js/jcanvas.js
Normal file
|
@ -0,0 +1,524 @@
|
|||
/*!
|
||||
jCanvas v2.2.1
|
||||
Caleb Evans
|
||||
2.2.1 revisions by Thinkyhead
|
||||
*/
|
||||
|
||||
(function($, document, Math, Number, undefined) {
|
||||
|
||||
// jC global object
|
||||
var jC = {};
|
||||
jC.originals = {
|
||||
width: 20,
|
||||
height: 20,
|
||||
cornerRadius: 0,
|
||||
fillStyle: 'transparent',
|
||||
strokeStyle: 'transparent',
|
||||
strokeWidth: 5,
|
||||
strokeCap: 'butt',
|
||||
strokeJoin: 'miter',
|
||||
shadowX: 0,
|
||||
shadowY: 0,
|
||||
shadowBlur: 10,
|
||||
shadowColor: 'transparent',
|
||||
x: 0, y: 0,
|
||||
x1: 0, y1: 0,
|
||||
radius: 10,
|
||||
start: 0,
|
||||
end: 360,
|
||||
ccw: false,
|
||||
inDegrees: true,
|
||||
fromCenter: true,
|
||||
closed: false,
|
||||
sides: 3,
|
||||
angle: 0,
|
||||
text: '',
|
||||
font: 'normal 12pt sans-serif',
|
||||
align: 'center',
|
||||
baseline: 'middle',
|
||||
source: '',
|
||||
repeat: 'repeat'
|
||||
};
|
||||
// Duplicate original defaults
|
||||
jC.defaults = $.extend({}, jC.originals);
|
||||
|
||||
// Set global properties
|
||||
function setGlobals(context, map) {
|
||||
context.fillStyle = map.fillStyle;
|
||||
context.strokeStyle = map.strokeStyle;
|
||||
context.lineWidth = map.strokeWidth;
|
||||
context.lineCap = map.strokeCap;
|
||||
context.lineJoin = map.strokeJoin;
|
||||
context.shadowOffsetX = map.shadowX;
|
||||
context.shadowOffsetY = map.shadowY;
|
||||
context.shadowBlur = map.shadowBlur;
|
||||
context.shadowColor = map.shadowColor;
|
||||
}
|
||||
|
||||
// Close path if chosen
|
||||
function closePath(context, map) {
|
||||
if (map.closed === true) {
|
||||
context.closePath();
|
||||
context.fill();
|
||||
context.stroke();
|
||||
} else {
|
||||
context.fill();
|
||||
context.stroke();
|
||||
context.closePath();
|
||||
}
|
||||
}
|
||||
|
||||
// Measure angles in degrees if chosen
|
||||
function checkUnits(map) {
|
||||
if (map.inDegrees === true) {
|
||||
return Math.PI / 180;
|
||||
} else {
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
// Set canvas defaults
|
||||
$.fn.canvas = function(args) {
|
||||
// Reset defaults if no value is passed
|
||||
if (typeof args === 'undefined') {
|
||||
jC.defaults = jC.originals;
|
||||
} else {
|
||||
jC.defaults = $.extend({}, jC.defaults, args);
|
||||
}
|
||||
return this;
|
||||
};
|
||||
|
||||
// Load canvas
|
||||
$.fn.loadCanvas = function(context) {
|
||||
if (typeof context === 'undefined') {context = '2d';}
|
||||
return this[0].getContext(context);
|
||||
};
|
||||
|
||||
// Create gradient
|
||||
$.fn.gradient = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
// Specify custom defaults
|
||||
gDefaults = {
|
||||
x1: 0, y1: 0,
|
||||
x2: 0, y2: 0,
|
||||
r1: 10, r2: 100
|
||||
},
|
||||
params = $.extend({}, gDefaults, args),
|
||||
gradient, stops = 0, percent, i;
|
||||
|
||||
// Create radial gradient if chosen
|
||||
if (typeof args.r1 === 'undefined' && typeof args.r2 === 'undefined') {
|
||||
gradient = ctx.createLinearGradient(params.x1, params.y1, params.x2, params.y2);
|
||||
} else {
|
||||
gradient = ctx.createRadialGradient(params.x1, params.y1, params.r1, params.x2, params.y2, params.r2);
|
||||
}
|
||||
|
||||
// Count number of color stops
|
||||
for (i=1; i<=Number.MAX_VALUE; i+=1) {
|
||||
if (params['c' + i]) {
|
||||
stops += 1;
|
||||
} else {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Calculate color stop percentages if absent
|
||||
for (i=1; i<=stops; i+=1) {
|
||||
percent = Math.round((100 / (stops-1)) * (i-1)) / 100;
|
||||
if (typeof params['s' + i] === 'undefined') {
|
||||
params['s' + i] = percent;
|
||||
}
|
||||
gradient.addColorStop(params['s' + i], params['c' + i]);
|
||||
}
|
||||
return gradient;
|
||||
};
|
||||
|
||||
// Create pattern
|
||||
$.fn.pattern = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args),
|
||||
pattern,
|
||||
img = document.createElement('img');
|
||||
img.src = params.source;
|
||||
|
||||
// Create pattern
|
||||
function create() {
|
||||
if (img.complete === true) {
|
||||
// Create pattern
|
||||
pattern = ctx.createPattern(img, params.repeat);
|
||||
} else {
|
||||
throw "The pattern has not loaded yet";
|
||||
}
|
||||
}
|
||||
try {
|
||||
create();
|
||||
} catch(error) {
|
||||
img.onload = create;
|
||||
}
|
||||
return pattern;
|
||||
};
|
||||
|
||||
// Clear canvas
|
||||
$.fn.clearCanvas = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args);
|
||||
|
||||
// Draw from center if chosen
|
||||
if (params.fromCenter === true) {
|
||||
params.x -= params.width / 2;
|
||||
params.y -= params.height / 2;
|
||||
}
|
||||
|
||||
// Clear entire canvas if chosen
|
||||
ctx.beginPath();
|
||||
if (typeof args === 'undefined') {
|
||||
ctx.clearRect(0, 0, this.width(), this.height());
|
||||
} else {
|
||||
ctx.clearRect(params.x, params.y, params.width, params.height);
|
||||
}
|
||||
ctx.closePath();
|
||||
return this;
|
||||
};
|
||||
|
||||
// Save canvas
|
||||
$.fn.saveCanvas = function() {
|
||||
var ctx = this.loadCanvas();
|
||||
ctx.save();
|
||||
return this;
|
||||
};
|
||||
|
||||
// Restore canvas
|
||||
$.fn.restoreCanvas = function() {
|
||||
var ctx = this.loadCanvas();
|
||||
ctx.restore();
|
||||
return this;
|
||||
};
|
||||
|
||||
// Scale canvas
|
||||
$.fn.scaleCanvas = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args);
|
||||
ctx.save();
|
||||
ctx.translate(params.x, params.y);
|
||||
ctx.scale(params.width, params.height);
|
||||
ctx.translate(-params.x, -params.y)
|
||||
return this;
|
||||
};
|
||||
|
||||
// Translate canvas
|
||||
$.fn.translateCanvas = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args);
|
||||
ctx.save();
|
||||
ctx.translate(params.x, params.y);
|
||||
return this;
|
||||
};
|
||||
|
||||
// Rotate canvas
|
||||
$.fn.rotateCanvas = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args),
|
||||
toRad = checkUnits(params);
|
||||
|
||||
ctx.save();
|
||||
ctx.translate(params.x, params.y);
|
||||
ctx.rotate(params.angle * toRad);
|
||||
ctx.translate(-params.x, -params.y);
|
||||
return this;
|
||||
};
|
||||
|
||||
// Draw rectangle
|
||||
$.fn.drawRect = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args),
|
||||
toRad = checkUnits(params),
|
||||
x1, y1, x2, y2, r;
|
||||
setGlobals(ctx, params);
|
||||
|
||||
// Draw from center if chosen
|
||||
if (params.fromCenter === true) {
|
||||
params.x -= params.width / 2;
|
||||
params.y -= params.height / 2;
|
||||
}
|
||||
|
||||
// Draw rounded rectangle if chosen
|
||||
if (params.cornerRadius > 0) {
|
||||
x1 = params.x;
|
||||
y1 = params.y;
|
||||
x2 = params.x + params.width;
|
||||
y2 = params.y + params.height;
|
||||
r = params.cornerRadius;
|
||||
if ((x2 - x1) - (2 * r) < 0) {
|
||||
r = (x2 - x1) / 2;
|
||||
}
|
||||
if ((y2 - y1) - (2 * r) < 0) {
|
||||
r = (y2 - y1) / 2;
|
||||
}
|
||||
ctx.beginPath();
|
||||
ctx.moveTo(x1+r,y1);
|
||||
ctx.lineTo(x2-r,y1);
|
||||
ctx.arc(x2-r, y1+r, r, 270*toRad, 360*toRad, false);
|
||||
ctx.lineTo(x2,y2-r);
|
||||
ctx.arc(x2-r, y2-r, r, 0, 90*toRad, false);
|
||||
ctx.lineTo(x1+r,y2);
|
||||
ctx.arc(x1+r, y2-r, r, 90*toRad, 180*toRad, false);
|
||||
ctx.lineTo(x1,y1+r);
|
||||
ctx.arc(x1+r, y1+r, r, 180*toRad, 270*toRad, false);
|
||||
ctx.fill();
|
||||
ctx.stroke();
|
||||
ctx.closePath();
|
||||
} else {
|
||||
ctx.fillRect(params.x, params.y, params.width, params.height);
|
||||
ctx.strokeRect(params.x, params.y, params.width, params.height);
|
||||
}
|
||||
return this;
|
||||
};
|
||||
|
||||
// Draw arc
|
||||
$.fn.drawArc = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args),
|
||||
toRad = checkUnits(params);
|
||||
setGlobals(ctx, params);
|
||||
|
||||
// Draw from center if chosen
|
||||
if (params.fromCenter === false) {
|
||||
params.x += params.radius;
|
||||
params.y += params.radius;
|
||||
}
|
||||
|
||||
ctx.beginPath();
|
||||
ctx.arc(params.x, params.y, params.radius, (params.start*toRad)-(Math.PI/2), (params.end*toRad)-(Math.PI/2), params.ccw);
|
||||
// Close path if chosen
|
||||
closePath(ctx, params);
|
||||
return this;
|
||||
};
|
||||
|
||||
// Draw ellipse
|
||||
$.fn.drawEllipse = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args),
|
||||
controlW = params.width * (4/3);
|
||||
setGlobals(ctx, params);
|
||||
|
||||
// Draw from center if chosen
|
||||
if (params.fromCenter === false) {
|
||||
params.x += params.width / 2;
|
||||
params.y += params.height / 2;
|
||||
}
|
||||
|
||||
// Increment coordinates to prevent negative values
|
||||
params.x += 1e-10;
|
||||
params.y += 1e-10;
|
||||
|
||||
// Create ellipse
|
||||
ctx.beginPath();
|
||||
ctx.moveTo(params.x, params.y-params.height/2);
|
||||
ctx.bezierCurveTo(params.x-controlW/2,params.y-params.height/2,
|
||||
params.x-controlW/2,params.y+params.height/2,
|
||||
params.x,params.y+params.height/2);
|
||||
ctx.bezierCurveTo(params.x+controlW/2,params.y+params.height/2,
|
||||
params.x+controlW/2,params.y-params.height/2,
|
||||
params.x,params.y-params.height/2);
|
||||
ctx.closePath();
|
||||
ctx.fill();
|
||||
ctx.stroke();
|
||||
return this;
|
||||
};
|
||||
|
||||
// Draw line
|
||||
$.fn.drawLine = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args),
|
||||
max = Number.MAX_VALUE, l,
|
||||
lx, ly;
|
||||
setGlobals(ctx, params);
|
||||
|
||||
// Draw each point
|
||||
ctx.beginPath();
|
||||
ctx.moveTo(params.x1, params.y1);
|
||||
for (l=2; l<max; l+=1) {
|
||||
lx = params['x' + l];
|
||||
ly = params['y' + l];
|
||||
// Stop loop when all points are drawn
|
||||
if (typeof lx === 'undefined' || typeof ly === 'undefined') {
|
||||
break;
|
||||
}
|
||||
ctx.lineTo(lx, ly);
|
||||
}
|
||||
// Close path if chosen
|
||||
closePath(ctx, params);
|
||||
return this;
|
||||
};
|
||||
|
||||
// Draw quadratic curve
|
||||
$.fn.drawQuad = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args),
|
||||
max = Number.MAX_VALUE, l,
|
||||
lx, ly, lcx, lcy;
|
||||
setGlobals(ctx, params);
|
||||
|
||||
// Draw each point
|
||||
ctx.beginPath();
|
||||
ctx.moveTo(params.x1, params.y1);
|
||||
for (l=2; l<max; l+=1) {
|
||||
lx = params['x' + l];
|
||||
if (typeof lx === 'undefined') break;
|
||||
ly = params['y' + l];
|
||||
if (typeof ly === 'undefined') break;
|
||||
lcx = params['cx' + (l-1)];
|
||||
if (typeof lcx === 'undefined') break;
|
||||
lcy = params['cy' + (l-1)];
|
||||
if (typeof lcy === 'undefined') break;
|
||||
ctx.quadraticCurveTo(lcx, lcy, lx, ly);
|
||||
}
|
||||
// Close path if chosen
|
||||
closePath(ctx, params);
|
||||
return this;
|
||||
};
|
||||
|
||||
// Draw Bezier curve
|
||||
$.fn.drawBezier = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args),
|
||||
max = Number.MAX_VALUE,
|
||||
l=2, lc=1, lx, ly, lcx1, lcy1, lcx2, lcy2, i;
|
||||
setGlobals(ctx, params);
|
||||
|
||||
// Draw each point
|
||||
ctx.beginPath();
|
||||
ctx.moveTo(params.x1, params.y1);
|
||||
for (i=2; i<max; i+=1) {
|
||||
lx = params['x' + l];
|
||||
if (typeof lx === 'undefined') break;
|
||||
ly = params['y' + l];
|
||||
if (typeof ly === 'undefined') break;
|
||||
lcx1 = params['cx' + lc];
|
||||
if (typeof lcx1 === 'undefined') break;
|
||||
lcy1 = params['cy' + lc];
|
||||
if (typeof lcy1 === 'undefined') break;
|
||||
lcx2 = params['cx' + (lc+1)];
|
||||
if (typeof lcx2 === 'undefined') break;
|
||||
lcy2 = params['cy' + (lc+1)];
|
||||
if (typeof lcy2 === 'undefined') break;
|
||||
ctx.bezierCurveTo(lcx1, lcy1, lcx2, lcy2, lx, ly);
|
||||
l += 1;
|
||||
lc += 2;
|
||||
}
|
||||
// Close path if chosen
|
||||
closePath(ctx, params);
|
||||
return this;
|
||||
};
|
||||
|
||||
// Draw text
|
||||
$.fn.drawText = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args);
|
||||
setGlobals(ctx, params);
|
||||
|
||||
// Set text-specific properties
|
||||
ctx.textBaseline = params.baseline;
|
||||
ctx.textAlign = params.align;
|
||||
ctx.font = params.font;
|
||||
|
||||
ctx.strokeText(params.text, params.x, params.y);
|
||||
ctx.fillText(params.text, params.x, params.y);
|
||||
return this;
|
||||
};
|
||||
|
||||
// Draw image
|
||||
$.fn.drawImage = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args),
|
||||
// Define image source
|
||||
img = document.createElement('img');
|
||||
img.src = params.source;
|
||||
setGlobals(ctx, params);
|
||||
|
||||
// Draw image function
|
||||
function draw() {
|
||||
if (img.complete) {
|
||||
|
||||
var scaleFac = img.width / img.height;
|
||||
|
||||
// If width/height are specified
|
||||
if (typeof args.width !== 'undefined' && typeof args.height !== 'undefined') {
|
||||
img.width = args.width;
|
||||
img.height = args.height;
|
||||
// If width is specified
|
||||
} else if (typeof args.width !== 'undefined' && typeof args.height === 'undefined') {
|
||||
img.width = args.width;
|
||||
img.height = img.width / scaleFac;
|
||||
// If height is specified
|
||||
} else if (typeof args.width === 'undefined' && typeof args.height !== 'undefined') {
|
||||
img.height = args.height;
|
||||
img.width = img.height * scaleFac;
|
||||
}
|
||||
|
||||
// Draw from center if chosen
|
||||
if (params.fromCenter === true) {
|
||||
params.x -= img.width / 2;
|
||||
params.y -= img.height / 2;
|
||||
}
|
||||
|
||||
// Draw image
|
||||
ctx.drawImage(img, params.x, params.y, img.width, img.height);
|
||||
} else {
|
||||
throw "The image has not loaded yet.";
|
||||
}
|
||||
}
|
||||
|
||||
function dodraw() {
|
||||
// console.log("dodraw...");
|
||||
try {
|
||||
// console.log("dodraw...try...");
|
||||
draw();
|
||||
}
|
||||
catch(error) {
|
||||
// console.log("dodraw...catch: " + error);
|
||||
}
|
||||
}
|
||||
|
||||
// Draw image if already loaded
|
||||
// console.log("--------------------");
|
||||
// console.log("drawImage " + img.src);
|
||||
try {
|
||||
// console.log("try...");
|
||||
draw();
|
||||
} catch(error) {
|
||||
// console.log("catch: " + error);
|
||||
img.onload = dodraw;
|
||||
}
|
||||
return this;
|
||||
};
|
||||
|
||||
// Draw polygon
|
||||
$.fn.drawPolygon = function(args) {
|
||||
var ctx = this.loadCanvas(),
|
||||
params = $.extend({}, jC.defaults, args),
|
||||
theta, dtheta, x, y,
|
||||
toRad = checkUnits(params), i;
|
||||
setGlobals(ctx, params);
|
||||
|
||||
if (params.sides >= 3) {
|
||||
// Calculate points and draw
|
||||
theta = (Math.PI/2) + (Math.PI/params.sides) + (params.angle*toRad);
|
||||
dtheta = (Math.PI*2) / params.sides;
|
||||
for (i=0; i<params.sides; i+=1) {
|
||||
x = params.x + (params.radius * Math.cos(theta)) + 1e-10;
|
||||
y = params.y + (params.radius * Math.sin(theta)) + 1e-10;
|
||||
if (params.fromCenter === false) {
|
||||
x += params.radius;
|
||||
y += params.radius;
|
||||
}
|
||||
ctx.lineTo(x, y);
|
||||
theta += dtheta;
|
||||
}
|
||||
closePath(ctx, params);
|
||||
}
|
||||
return this;
|
||||
};
|
||||
|
||||
return window.jCanvas = jC;
|
||||
}(jQuery, document, Math, Number));
|
4
Marlin/configurator/js/jquery-2.1.3.min.js
vendored
Normal file
220
Marlin/configurator/js/jstepper.js
Normal file
|
@ -0,0 +1,220 @@
|
|||
/*!
|
||||
* jQuery "stepper" Plugin
|
||||
* version 0.0.1
|
||||
* @requires jQuery v1.3.2 or later
|
||||
* @requires jCanvas
|
||||
*
|
||||
* Authored 2011-06-11 Scott Lahteine (thinkyhead.com)
|
||||
*
|
||||
* A very simple numerical stepper.
|
||||
* TODO: place arrows based on div size, make 50/50 width
|
||||
*
|
||||
* Usage example:
|
||||
*
|
||||
* $('#mydiv').jstepper({
|
||||
* min: 1,
|
||||
* max: 4,
|
||||
* val: 1,
|
||||
* arrowWidth: 15,
|
||||
* arrowHeight: '22px',
|
||||
* color: '#FFF',
|
||||
* acolor: '#F70',
|
||||
* hcolor: '#FF0',
|
||||
* id: 'select-me',
|
||||
* stepperClass: 'inner',
|
||||
* textStyle: {width:'1.5em',fontSize:'20px',textAlign:'center'},
|
||||
* onChange: function(v) { },
|
||||
* });
|
||||
*
|
||||
*/
|
||||
;(function($) {
|
||||
var un = 'undefined';
|
||||
|
||||
$.jstepperArrows = [
|
||||
{ name:'prev', poly:[[1.0,0],[0,0.5],[1.0,1.0]] },
|
||||
{ name:'next', poly:[[0,0],[1.0,0.5],[0,1.0]] }
|
||||
];
|
||||
|
||||
$.fn.jstepper = function(args) {
|
||||
|
||||
return this.each(function() {
|
||||
|
||||
var defaults = {
|
||||
min: 1,
|
||||
max: null,
|
||||
val: null,
|
||||
active: true,
|
||||
placeholder: null,
|
||||
arrowWidth: 0,
|
||||
arrowHeight: 0,
|
||||
color: '#FFF',
|
||||
hcolor: '#FF0',
|
||||
acolor: '#F80',
|
||||
id: '',
|
||||
stepperClass: '',
|
||||
textStyle: '',
|
||||
onChange: (function(v){ if (typeof console.log !== 'undefined') console.log("val="+v); })
|
||||
};
|
||||
|
||||
args = $.extend(defaults, args || {});
|
||||
|
||||
var min = args.min * 1,
|
||||
max = (args.max !== null) ? args.max * 1 : min,
|
||||
span = max - min + 1,
|
||||
val = (args.val !== null) ? args.val * 1 : min,
|
||||
active = !args.disabled,
|
||||
placeholder = args.placeholder,
|
||||
arrowWidth = 1 * args.arrowWidth.toString().replace(/px/,''),
|
||||
arrowHeight = 1 * args.arrowHeight.toString().replace(/px/,''),
|
||||
color = args.color,
|
||||
hcolor = args.hcolor,
|
||||
acolor = args.acolor,
|
||||
$prev = $('<a href="#prev" style="cursor:w-resize;"><canvas/></a>'),
|
||||
$marq = $('<div class="number"/>').css({float:'left',textAlign:'center'}),
|
||||
$next = $('<a href="#next" style="cursor:e-resize;"><canvas/></a>'),
|
||||
arrow = [ $prev.find('canvas')[0], $next.find('canvas')[0] ],
|
||||
$stepper = $('<span class="jstepper"/>').append($prev).append($marq).append($next).append('<div style="clear:both;"/>'),
|
||||
onChange = args.onChange;
|
||||
|
||||
if (args.id) $stepper[0].id = args.id;
|
||||
if (args.stepperClass) $stepper.addClass(args.stepperClass);
|
||||
if (args.textStyle) $marq.css(args.textStyle);
|
||||
|
||||
// replace a span, but embed elsewhere
|
||||
if (this.tagName == 'SPAN') {
|
||||
var previd = this.id;
|
||||
$(this).replaceWith($stepper);
|
||||
if (previd) $stepper.attr('id',previd);
|
||||
}
|
||||
else {
|
||||
$(this).append($stepper);
|
||||
}
|
||||
|
||||
// hook to call functions on this object
|
||||
$stepper[0].ui = {
|
||||
|
||||
refresh: function() {
|
||||
this.updateNumber();
|
||||
this._drawArrow(0, 1);
|
||||
this._drawArrow(1, 1);
|
||||
return this;
|
||||
},
|
||||
|
||||
_drawArrow: function(i,state) {
|
||||
var $elm = $(arrow[i]),
|
||||
desc = $.jstepperArrows[i],
|
||||
fillStyle = (state == 2) ? hcolor : (state == 3) ? acolor : color,
|
||||
draw = { fillStyle: fillStyle },
|
||||
w = $elm.width(), h = $elm.height();
|
||||
|
||||
if (w <= 0) w = $elm.attr('width');
|
||||
if (h <= 0) h = $elm.attr('height');
|
||||
|
||||
$.each(desc.poly,function(i,v){
|
||||
++i;
|
||||
draw['x'+i] = v[0] * w;
|
||||
draw['y'+i] = v[1] * h;
|
||||
});
|
||||
$elm.restoreCanvas().clearCanvas().drawLine(draw);
|
||||
},
|
||||
|
||||
updateNumber: function() {
|
||||
$marq.html((active || placeholder === null) ? val.toString() : placeholder);
|
||||
return this;
|
||||
},
|
||||
|
||||
_doclick: function(i) {
|
||||
this.add(i ? 1 : -1);
|
||||
this._drawArrow(i, 3);
|
||||
var self = this;
|
||||
setTimeout(function(){ self._drawArrow(i, 2); }, 50);
|
||||
},
|
||||
|
||||
add: function(x) {
|
||||
val = (((val - min) + x + span) % span) + min;
|
||||
this.updateNumber();
|
||||
this.didChange(val);
|
||||
return this;
|
||||
},
|
||||
|
||||
min: function(v) {
|
||||
if (typeof v === un) return min;
|
||||
this.setRange(v,max);
|
||||
return this;
|
||||
},
|
||||
|
||||
max: function(v) {
|
||||
if (typeof v === un) return max;
|
||||
this.setRange(min,v);
|
||||
return this;
|
||||
},
|
||||
|
||||
val: function(v) {
|
||||
if (typeof v === un) return val;
|
||||
val = (((v - min) + span) % span) + min;
|
||||
this.updateNumber();
|
||||
return this;
|
||||
},
|
||||
|
||||
setRange: function(lo, hi, ini) {
|
||||
if (lo > hi) hi = (lo += hi -= lo) - hi;
|
||||
min = lo; max = hi; span = hi - lo + 1;
|
||||
if (typeof ini !== un) val = ini;
|
||||
if (val < min) val = min;
|
||||
if (val > max) val = max;
|
||||
this.updateNumber();
|
||||
return this;
|
||||
},
|
||||
|
||||
active: function(a) {
|
||||
if (typeof a === un) return active;
|
||||
(active = a) ? $marq.removeClass('inactive') : $marq.addClass('inactive');
|
||||
this.updateNumber();
|
||||
return this;
|
||||
},
|
||||
|
||||
disable: function() { this.active(false); return this; },
|
||||
enable: function() { this.active(true); return this; },
|
||||
|
||||
clearPlaceholder: function() {
|
||||
this.setPlaceholder(null);
|
||||
return this;
|
||||
},
|
||||
setPlaceholder: function(p) {
|
||||
placeholder = p;
|
||||
if (!active) this.updateNumber();
|
||||
return this;
|
||||
},
|
||||
|
||||
didChange: onChange
|
||||
|
||||
};
|
||||
|
||||
// set hover and click for each arrow
|
||||
$.each($.jstepperArrows, function(i,desc) {
|
||||
var $elm = $(arrow[i]),
|
||||
w = arrowWidth ? arrowWidth : $elm.width() ? $elm.width() : 15,
|
||||
h = arrowHeight ? arrowHeight : $elm.height() ? $elm.height() : 24;
|
||||
$elm[0]._index = i;
|
||||
$elm
|
||||
.css({float:'left'})
|
||||
.attr({width:w,height:h,'class':desc.name})
|
||||
.hover(
|
||||
function(e) { $stepper[0].ui._drawArrow(e.target._index, 2); },
|
||||
function(e) { $stepper[0].ui._drawArrow(e.target._index, 1); }
|
||||
)
|
||||
.click(function(e){
|
||||
$stepper[0].ui._doclick(e.target._index);
|
||||
return false;
|
||||
});
|
||||
});
|
||||
|
||||
// init the visuals first time
|
||||
$stepper[0].ui.refresh();
|
||||
|
||||
}); // this.each
|
||||
|
||||
}; // $.fn.jstepper
|
||||
|
||||
})( jQuery );
|
||||
|
14
Marlin/configurator/js/jszip.min.js
vendored
Executable file
|
@ -24,9 +24,9 @@
|
|||
#define BLEN_A 0
|
||||
#define BLEN_B 1
|
||||
#define BLEN_C 2
|
||||
#define EN_A (1<<BLEN_A)
|
||||
#define EN_B (1<<BLEN_B)
|
||||
#define EN_C (1<<BLEN_C)
|
||||
#define EN_A BIT(BLEN_A)
|
||||
#define EN_B BIT(BLEN_B)
|
||||
#define EN_C BIT(BLEN_C)
|
||||
#define LCD_CLICKED (buttons&EN_C)
|
||||
#endif
|
||||
|
||||
|
|
852
Marlin/example_configurations/Felix/Configuration.h
Normal file
|
@ -0,0 +1,852 @@
|
|||
#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://youtu.be/wAL9d7FgInk
|
||||
* http://calculator.josefprusa.cz
|
||||
* http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
|
||||
* http://www.thingiverse.com/thing:5573
|
||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||
* 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 ===============================
|
||||
//===========================================================================
|
||||
// For a Delta printer replace the configuration files with the files in the
|
||||
// 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.
|
||||
#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 "(none, default config)" // Who made the changes.
|
||||
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
|
||||
//#define STRING_SPLASH_LINE2 STRING_VERSION_CONFIG_H // will be shown during bootup in line2
|
||||
|
||||
// SERIAL_PORT selects which serial port should be used for communication with the host.
|
||||
// This allows the connection of wireless adapters (for instance) to non-default port pins.
|
||||
// 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
|
||||
#define BAUDRATE 250000
|
||||
|
||||
// This enables the serial port associated to the Bluetooth interface
|
||||
//#define BTENABLED // Enable BT interface on AT90USB devices
|
||||
|
||||
// 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_FELIX2
|
||||
#endif
|
||||
|
||||
// Define this to set a custom name for your generic Mendel,
|
||||
// #define CUSTOM_MENDEL_NAME "This Mendel"
|
||||
|
||||
// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
|
||||
// You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
|
||||
// #define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
||||
|
||||
// This defines the number of extruders
|
||||
#define EXTRUDERS 1
|
||||
|
||||
//// The following define selects which power supply you have. Please choose the one that matches your setup
|
||||
// 1 = ATX
|
||||
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
|
||||
|
||||
#define POWER_SUPPLY 1
|
||||
|
||||
// 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 ============================
|
||||
//===========================================================================
|
||||
//
|
||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||
//
|
||||
//// Temperature sensor settings:
|
||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||
// -1 is thermocouple with AD595
|
||||
// 0 is not used
|
||||
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
|
||||
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
|
||||
// 3 is Mendel-parts thermistor (4.7k pullup)
|
||||
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
|
||||
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
|
||||
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
|
||||
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
|
||||
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
|
||||
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
|
||||
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
|
||||
// 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
|
||||
//
|
||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||
// (but gives greater accuracy and more stable PID)
|
||||
// 51 is 100k thermistor - EPCOS (1k pullup)
|
||||
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
|
||||
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
|
||||
//
|
||||
// 1047 is Pt1000 with 4k7 pullup
|
||||
// 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
|
||||
#define TEMP_SENSOR_2 0
|
||||
#define TEMP_SENSOR_3 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
|
||||
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
|
||||
//#define TEMP_SENSOR_1_AS_REDUNDANT
|
||||
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
|
||||
|
||||
// Actual temperature must be close to target for this long before M109 returns success
|
||||
#define TEMP_RESIDENCY_TIME 15 // (seconds)
|
||||
#define TEMP_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one
|
||||
#define TEMP_WINDOW 1 // (degC) Window around target to start the residency timer x degC early.
|
||||
|
||||
// The minimal temperature defines the temperature below which the heater will not be enabled It is used
|
||||
// to check that the wiring to the thermistor is not broken.
|
||||
// Otherwise this would lead to the heater being powered on all the time.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
#define HEATER_1_MINTEMP 5
|
||||
#define HEATER_2_MINTEMP 5
|
||||
#define HEATER_3_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
|
||||
// When temperature exceeds max temp, your heater will be switched off.
|
||||
// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
|
||||
// You should use MINTEMP for thermistor short/failure protection.
|
||||
#define HEATER_0_MAXTEMP 275
|
||||
#define HEATER_1_MAXTEMP 275
|
||||
#define HEATER_2_MAXTEMP 275
|
||||
#define HEATER_3_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
|
||||
// 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.
|
||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
||||
|
||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||
//#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 ================================
|
||||
//===========================================================================
|
||||
// PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning
|
||||
|
||||
// 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 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 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
|
||||
|
||||
// Felix 2.0+ electronics with v4 Hotend
|
||||
#define DEFAULT_Kp 12
|
||||
#define DEFAULT_Ki 0.84
|
||||
#define DEFAULT_Kd 85
|
||||
|
||||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//===========================================================================
|
||||
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
|
||||
//
|
||||
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
|
||||
// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
|
||||
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
|
||||
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
|
||||
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
|
||||
// shouldn't use bed PID until someone else verifies your hardware works.
|
||||
// If this is enabled, find your own PID constants below.
|
||||
#define PIDTEMPBED
|
||||
//
|
||||
//#define BED_LIMIT_SWITCHING
|
||||
|
||||
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||
|
||||
#ifdef PIDTEMPBED
|
||||
// Felix Foil Heater
|
||||
#define DEFAULT_bedKp 103.37
|
||||
#define DEFAULT_bedKi 2.79
|
||||
#define DEFAULT_bedKd 956.94
|
||||
|
||||
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
||||
#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
|
||||
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
|
||||
#define PREVENT_LENGTHY_EXTRUDE
|
||||
|
||||
#define EXTRUDE_MINTEMP 170
|
||||
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
|
||||
|
||||
//===========================================================================
|
||||
//============================= Thermal Runaway Protection ==================
|
||||
//===========================================================================
|
||||
/*
|
||||
This is a feature to protect your printer from burn up in flames if it has
|
||||
a thermistor coming off place (this happened to a friend of mine recently and
|
||||
motivated me writing this feature).
|
||||
|
||||
The issue: If a thermistor come off, it will read a lower temperature than actual.
|
||||
The system will turn the heater on forever, burning up the filament and anything
|
||||
else around.
|
||||
|
||||
After the temperature reaches the target for the first time, this feature will
|
||||
start measuring for how long the current temperature stays below the target
|
||||
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
|
||||
|
||||
If it stays longer than _PERIOD, it means the thermistor temperature
|
||||
cannot catch up with the target, so something *may be* wrong. Then, to be on the
|
||||
safe side, the system will he halt.
|
||||
|
||||
Bear in mind the count down will just start AFTER the first time the
|
||||
thermistor temperature is over the target, so you will have no problem if
|
||||
your extruder heater takes 2 minutes to hit the target on heating.
|
||||
|
||||
*/
|
||||
// If you want to enable this feature for all your extruder heaters,
|
||||
// uncomment the 2 defines below:
|
||||
|
||||
// Parameters for all extruder heaters
|
||||
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 60 //in seconds
|
||||
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 5 // in degree Celsius
|
||||
|
||||
// If you want to enable this feature for your bed heater,
|
||||
// uncomment the 2 defines below:
|
||||
|
||||
// Parameters for the bed heater
|
||||
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 30 //in seconds
|
||||
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 5// in degree Celsius
|
||||
|
||||
|
||||
//===========================================================================
|
||||
//============================= Mechanical Settings =========================
|
||||
//===========================================================================
|
||||
|
||||
// Uncomment the following line 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
|
||||
|
||||
#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
|
||||
|
||||
#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 = 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 = 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.
|
||||
#define DISABLE_MAX_ENDSTOPS
|
||||
//#define DISABLE_MIN_ENDSTOPS
|
||||
|
||||
// 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
|
||||
#define Z_ENABLE_ON 0
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
#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 true // 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
|
||||
|
||||
// ENDSTOP SETTINGS:
|
||||
// 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
|
||||
|
||||
#define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
|
||||
#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 255
|
||||
#define X_MIN_POS 0
|
||||
#define Y_MAX_POS 205
|
||||
#define Y_MIN_POS 0
|
||||
#define Z_MAX_POS 235
|
||||
#define Z_MIN_POS 0
|
||||
|
||||
#define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)
|
||||
#define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
|
||||
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
|
||||
|
||||
|
||||
//===========================================================================
|
||||
//============================= Bed Auto Leveling ===========================
|
||||
//===========================================================================
|
||||
|
||||
//#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
|
||||
|
||||
#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
|
||||
|
||||
// Use one of these defines to specify the origin
|
||||
// for a topographical map to be printed for your bed.
|
||||
enum { OriginBackLeft, OriginFrontLeft, OriginBackRight, OriginFrontRight };
|
||||
#define TOPO_ORIGIN OriginFrontLeft
|
||||
|
||||
// set 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
|
||||
|
||||
// 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 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
|
||||
|
||||
#define ABL_PROBE_PT_1_X 15
|
||||
#define ABL_PROBE_PT_1_Y 180
|
||||
#define ABL_PROBE_PT_2_X 15
|
||||
#define ABL_PROBE_PT_2_Y 20
|
||||
#define ABL_PROBE_PT_3_X 170
|
||||
#define ABL_PROBE_PT_3_Y 20
|
||||
|
||||
#endif // AUTO_BED_LEVELING_GRID
|
||||
|
||||
|
||||
// these are the 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 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
|
||||
|
||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min
|
||||
|
||||
#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.
|
||||
// You MUST HAVE the SERVO_ENDSTOPS defined to use here a value higher than zero otherwise your code will not compile.
|
||||
|
||||
// #define PROBE_SERVO_DEACTIVATION_DELAY 300
|
||||
|
||||
|
||||
//If you have enabled the Bed Auto Leveling and are using the same Z Probe for Z Homing,
|
||||
//it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
||||
|
||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with probe outside the bed area.
|
||||
// When defined, it will:
|
||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled
|
||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing
|
||||
// - Position the probe in a defined XY point before Z Homing when homing all axis (G28)
|
||||
// - Block Z homing only when the probe is outside bed area.
|
||||
|
||||
#ifdef Z_SAFE_HOMING
|
||||
|
||||
#define Z_SAFE_HOMING_X_POINT (X_MAX_LENGTH/2) // X point for Z homing when homing all axis (G28)
|
||||
#define Z_SAFE_HOMING_Y_POINT (Y_MAX_LENGTH/2) // Y point for Z homing when homing all axis (G28)
|
||||
|
||||
#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
|
||||
|
||||
|
||||
// The position of the homing switches
|
||||
//#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:
|
||||
// For deltabots this means top and center of the Cartesian print volume.
|
||||
#define MANUAL_X_HOME_POS 0
|
||||
#define MANUAL_Y_HOME_POS 0
|
||||
#define MANUAL_Z_HOME_POS 0
|
||||
//#define MANUAL_Z_HOME_POS 402 // For delta: Distance between nozzle and print surface after homing.
|
||||
|
||||
//// MOVEMENT SETTINGS
|
||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||
#define HOMING_FEEDRATE {50*60, 50*60, 4*60, 0} // set the homing speeds (mm/min)
|
||||
|
||||
// default settings
|
||||
|
||||
// default steps per unit for Felix 2.0/3.0: 0.00249mm x/y rounding error with 3mm pitch HTD belt and 14 tooth pulleys. 0 z error.
|
||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {76.190476, 76.190476, 1600, 164}
|
||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
|
||||
#define DEFAULT_MAX_ACCELERATION {5000,5000,100,80000} // 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 1750 //1500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||
#define DEFAULT_RETRACT_ACCELERATION 5000 // X, Y, Z and E max acceleration in mm/s^2 for r 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).
|
||||
// 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
|
||||
|
||||
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
|
||||
#define DEFAULT_XYJERK 10 // (mm/sec)
|
||||
#define DEFAULT_ZJERK 0.3 //0.4 // (mm/sec)
|
||||
#define DEFAULT_EJERK 5.0 // (mm/sec)
|
||||
|
||||
|
||||
//=============================================================================
|
||||
//============================= Additional Features ===========================
|
||||
//=============================================================================
|
||||
|
||||
// Custom M code points
|
||||
#define CUSTOM_M_CODES
|
||||
#ifdef CUSTOM_M_CODES
|
||||
#define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
|
||||
#define Z_PROBE_OFFSET_RANGE_MIN -15
|
||||
#define Z_PROBE_OFFSET_RANGE_MAX -5
|
||||
#endif
|
||||
|
||||
|
||||
// EEPROM
|
||||
// The microcontroller can store settings in the EEPROM, e.g. max velocity...
|
||||
// M500 - stores parameters in EEPROM
|
||||
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
||||
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
||||
//define this to enable EEPROM support
|
||||
//#define EEPROM_SETTINGS
|
||||
//to disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
|
||||
// please keep turned on if you can.
|
||||
//#define EEPROM_CHITCHAT
|
||||
|
||||
// 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 ABS_PREHEAT_HOTEND_TEMP 240
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
|
||||
|
||||
//==============================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°"
|
||||
//#define DISPLAY_CHARSET_HD44780_WESTERN // "ÄäÖöÜüß²³°" if you see a '~' instead of a 'arrow_right' at the right of submenuitems - this is the right one.
|
||||
|
||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||
//#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 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
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
//#define PANEL_ONE
|
||||
|
||||
// The MaKr3d Makr-Panel with graphic controller and SD support
|
||||
// http://reprap.org/wiki/MaKr3d_MaKrPanel
|
||||
//#define MAKRPANEL
|
||||
|
||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||
// http://panucatt.com
|
||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
||||
//#define VIKI2
|
||||
//#define miniVIKI
|
||||
|
||||
// The RepRapDiscount Smart Controller (white PCB)
|
||||
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
|
||||
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||
|
||||
// The GADGETS3D G3D LCD/SD Controller (blue PCB)
|
||||
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
|
||||
//#define G3D_PANEL
|
||||
|
||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||
//
|
||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||
|
||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
|
||||
//#define REPRAPWORLD_KEYPAD
|
||||
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // how much should be moved when a key is pressed, eg 10.0 means 10mm per click
|
||||
|
||||
// The Elefu RA Board Control Panel
|
||||
// http://www.elefu.com/index.php?route=product/product&product_id=53
|
||||
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
||||
//#define RA_CONTROL_PANEL
|
||||
|
||||
//automatic expansion
|
||||
#if defined (MAKRPANEL)
|
||||
#define DOGLCD
|
||||
#define SDSUPPORT
|
||||
#define ULTIPANEL
|
||||
#define NEWPANEL
|
||||
#define DEFAULT_LCD_CONTRAST 17
|
||||
#endif
|
||||
|
||||
#if defined(miniVIKI) || defined(VIKI2)
|
||||
#define ULTRA_LCD //general LCD support, also 16x2
|
||||
#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||
#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
|
||||
#ifdef miniVIKI
|
||||
#define DEFAULT_LCD_CONTRAST 95
|
||||
#else
|
||||
#define DEFAULT_LCD_CONTRAST 40
|
||||
#endif
|
||||
|
||||
#define ENCODER_PULSES_PER_STEP 4
|
||||
#define ENCODER_STEPS_PER_MENU_ITEM 1
|
||||
#endif
|
||||
|
||||
#if defined (PANEL_ONE)
|
||||
#define SDSUPPORT
|
||||
#define ULTIMAKERCONTROLLER
|
||||
#endif
|
||||
|
||||
#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
|
||||
#define DOGLCD
|
||||
#define U8GLIB_ST7920
|
||||
#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||
#endif
|
||||
|
||||
#if defined(ULTIMAKERCONTROLLER) || defined(REPRAP_DISCOUNT_SMART_CONTROLLER) || defined(G3D_PANEL)
|
||||
#define ULTIPANEL
|
||||
#define NEWPANEL
|
||||
#endif
|
||||
|
||||
#if defined(REPRAPWORLD_KEYPAD)
|
||||
#define NEWPANEL
|
||||
#define ULTIPANEL
|
||||
#endif
|
||||
#if defined(RA_CONTROL_PANEL)
|
||||
#define ULTIPANEL
|
||||
#define NEWPANEL
|
||||
#define LCD_I2C_TYPE_PCA8574
|
||||
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
|
||||
#endif
|
||||
|
||||
//I2C PANELS
|
||||
|
||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||
#ifdef LCD_I2C_SAINSMART_YWROBOT
|
||||
// This uses the LiquidCrystal_I2C library ( https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home )
|
||||
// Make sure it is placed in the Arduino libraries directory.
|
||||
#define LCD_I2C_TYPE_PCF8575
|
||||
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
|
||||
#define NEWPANEL
|
||||
#define ULTIPANEL
|
||||
#endif
|
||||
|
||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||
//#define LCD_I2C_PANELOLU2
|
||||
#ifdef LCD_I2C_PANELOLU2
|
||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
|
||||
// (v1.2.3 no longer requires you to define PANELOLU in the LiquidTWI2.h library header file)
|
||||
// Note: The PANELOLU2 encoder click input can either be directly connected to a pin
|
||||
// (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1).
|
||||
#define LCD_I2C_TYPE_MCP23017
|
||||
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
|
||||
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD
|
||||
#define NEWPANEL
|
||||
#define ULTIPANEL
|
||||
|
||||
#ifndef ENCODER_PULSES_PER_STEP
|
||||
#define ENCODER_PULSES_PER_STEP 4
|
||||
#endif
|
||||
|
||||
#ifndef ENCODER_STEPS_PER_MENU_ITEM
|
||||
#define ENCODER_STEPS_PER_MENU_ITEM 1
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef LCD_USE_I2C_BUZZER
|
||||
#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
||||
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
// Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
|
||||
//#define LCD_I2C_VIKI
|
||||
#ifdef LCD_I2C_VIKI
|
||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
|
||||
// Note: The pause/stop/resume LCD button pin should be connected to the Arduino
|
||||
// BTN_ENC pin (or set BTN_ENC to -1 if not used)
|
||||
#define LCD_I2C_TYPE_MCP23017
|
||||
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
|
||||
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later)
|
||||
#define NEWPANEL
|
||||
#define ULTIPANEL
|
||||
#endif
|
||||
|
||||
// Shift register panels
|
||||
// ---------------------
|
||||
// 2 wire Non-latching LCD SR from:
|
||||
// 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
|
||||
|
||||
|
||||
#ifdef ULTIPANEL
|
||||
#define NEWPANEL //enable this if you have a click-encoder panel
|
||||
#define SDSUPPORT
|
||||
#define ULTRA_LCD
|
||||
#ifdef DOGLCD // Change number of lines to match the DOG graphic display
|
||||
#define LCD_WIDTH 22
|
||||
#define LCD_HEIGHT 5
|
||||
#else
|
||||
#define LCD_WIDTH 20
|
||||
#define LCD_HEIGHT 4
|
||||
#endif
|
||||
#else //no panel but just LCD
|
||||
#ifdef ULTRA_LCD
|
||||
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
|
||||
#define LCD_WIDTH 22
|
||||
#define LCD_HEIGHT 5
|
||||
#else
|
||||
#define LCD_WIDTH 16
|
||||
#define LCD_HEIGHT 2
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// default LCD contrast for dogm-like LCD displays
|
||||
#ifdef DOGLCD
|
||||
# ifndef DEFAULT_LCD_CONTRAST
|
||||
# define DEFAULT_LCD_CONTRAST 32
|
||||
# endif
|
||||
#endif
|
||||
|
||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||
#define FAST_PWM_FAN
|
||||
|
||||
// Temperature status LEDs that display the hotend and bet temperature.
|
||||
// If all hotends and bed temperature and temperature setpoint are < 54C then the BLUE led is on.
|
||||
// Otherwise the RED led is on. There is 1C hysteresis.
|
||||
//#define TEMP_STAT_LEDS
|
||||
|
||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||
// which is not as annoying as with the hardware PWM. On the other hand, if this frequency
|
||||
// is too low, you should also increment SOFT_PWM_SCALE.
|
||||
//#define FAN_SOFT_PWM
|
||||
|
||||
// Incrementing this by 1 will double the software PWM frequency,
|
||||
// affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
|
||||
// However, control resolution will be halved for each increment;
|
||||
// at zero value, there are 128 effective control positions.
|
||||
#define SOFT_PWM_SCALE 0
|
||||
|
||||
// M240 Triggers a camera by emulating a Canon RC-1 Remote
|
||||
// Data from: http://www.doc-diy.net/photo/rc-1_hacked/
|
||||
// #define PHOTOGRAPH_PIN 23
|
||||
|
||||
// SF send wrong arc g-codes when using Arc Point as fillet procedure
|
||||
//#define SF_ARC_FIX
|
||||
|
||||
// Support for the BariCUDA Paste Extruder.
|
||||
//#define BARICUDA
|
||||
|
||||
//define BlinkM/CyzRgb Support
|
||||
//#define BLINKM
|
||||
|
||||
/*********************************************************************\
|
||||
* R/C SERVO support
|
||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||
**********************************************************************/
|
||||
|
||||
// Number of servos
|
||||
//
|
||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
||||
// set it manually if you have more servos than extruders and wish to manually control some
|
||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
||||
// If unsure, leave commented / disabled
|
||||
//
|
||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||
|
||||
// Servo Endstops
|
||||
//
|
||||
// This allows for servo actuated endstops, primary usage is for the Z Axis to eliminate calibration or bed height changes.
|
||||
// Use M206 command to correct for switch height offset to actual nozzle height. Store that setting with M500.
|
||||
//
|
||||
//#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1
|
||||
//#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 70,0} // X,Y,Z Axis Extend and Retract angles
|
||||
|
||||
/**********************************************************************\
|
||||
* Support for a filament diameter sensor
|
||||
* Also allows adjustment of diameter at print time (vs at slicing)
|
||||
* Single extruder only at this point (extruder 0)
|
||||
*
|
||||
* Motherboards
|
||||
* 34 - RAMPS1.4 - uses Analog input 5 on the AUX2 connector
|
||||
* 81 - Printrboard - Uses Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||
* 301 - Rambo - uses Analog input 3
|
||||
* Note may require analog pins to be defined for different motherboards
|
||||
**********************************************************************/
|
||||
// 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 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)
|
||||
|
||||
//defines used in the code
|
||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||
|
||||
//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status. Status will appear for 5 sec.
|
||||
//#define FILAMENT_LCD_DISPLAY
|
||||
|
||||
|
||||
#include "Configuration_adv.h"
|
||||
#include "thermistortables.h"
|
||||
|
||||
#endif //__CONFIGURATION_H
|
852
Marlin/example_configurations/Felix/Configuration_DUAL.h
Normal file
|
@ -0,0 +1,852 @@
|
|||
#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://youtu.be/wAL9d7FgInk
|
||||
* http://calculator.josefprusa.cz
|
||||
* http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
|
||||
* http://www.thingiverse.com/thing:5573
|
||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||
* 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 ===============================
|
||||
//===========================================================================
|
||||
// For a Delta printer replace the configuration files with the files in the
|
||||
// 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.
|
||||
#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 "(none, default config)" // Who made the changes.
|
||||
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
|
||||
//#define STRING_SPLASH_LINE2 STRING_VERSION_CONFIG_H // will be shown during bootup in line2
|
||||
|
||||
// SERIAL_PORT selects which serial port should be used for communication with the host.
|
||||
// This allows the connection of wireless adapters (for instance) to non-default port pins.
|
||||
// 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
|
||||
#define BAUDRATE 250000
|
||||
|
||||
// This enables the serial port associated to the Bluetooth interface
|
||||
//#define BTENABLED // Enable BT interface on AT90USB devices
|
||||
|
||||
// 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_FELIX2
|
||||
#endif
|
||||
|
||||
// Define this to set a custom name for your generic Mendel,
|
||||
// #define CUSTOM_MENDEL_NAME "This Mendel"
|
||||
|
||||
// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
|
||||
// You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
|
||||
// #define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
||||
|
||||
// This defines the number of extruders
|
||||
#define EXTRUDERS 2
|
||||
|
||||
//// The following define selects which power supply you have. Please choose the one that matches your setup
|
||||
// 1 = ATX
|
||||
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
|
||||
|
||||
#define POWER_SUPPLY 1
|
||||
|
||||
// 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 ============================
|
||||
//===========================================================================
|
||||
//
|
||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||
//
|
||||
//// Temperature sensor settings:
|
||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||
// -1 is thermocouple with AD595
|
||||
// 0 is not used
|
||||
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
|
||||
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
|
||||
// 3 is Mendel-parts thermistor (4.7k pullup)
|
||||
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
|
||||
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
|
||||
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
|
||||
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
|
||||
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
|
||||
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
|
||||
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
|
||||
// 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
|
||||
//
|
||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||
// (but gives greater accuracy and more stable PID)
|
||||
// 51 is 100k thermistor - EPCOS (1k pullup)
|
||||
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
|
||||
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
|
||||
//
|
||||
// 1047 is Pt1000 with 4k7 pullup
|
||||
// 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
|
||||
#define TEMP_SENSOR_2 0
|
||||
#define TEMP_SENSOR_3 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
|
||||
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
|
||||
//#define TEMP_SENSOR_1_AS_REDUNDANT
|
||||
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
|
||||
|
||||
// Actual temperature must be close to target for this long before M109 returns success
|
||||
#define TEMP_RESIDENCY_TIME 15 // (seconds)
|
||||
#define TEMP_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one
|
||||
#define TEMP_WINDOW 1 // (degC) Window around target to start the residency timer x degC early.
|
||||
|
||||
// The minimal temperature defines the temperature below which the heater will not be enabled It is used
|
||||
// to check that the wiring to the thermistor is not broken.
|
||||
// Otherwise this would lead to the heater being powered on all the time.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
#define HEATER_1_MINTEMP 5
|
||||
#define HEATER_2_MINTEMP 5
|
||||
#define HEATER_3_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
|
||||
// When temperature exceeds max temp, your heater will be switched off.
|
||||
// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
|
||||
// You should use MINTEMP for thermistor short/failure protection.
|
||||
#define HEATER_0_MAXTEMP 275
|
||||
#define HEATER_1_MAXTEMP 275
|
||||
#define HEATER_2_MAXTEMP 275
|
||||
#define HEATER_3_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
|
||||
// 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.
|
||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
||||
|
||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||
//#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 ================================
|
||||
//===========================================================================
|
||||
// PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning
|
||||
|
||||
// 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 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 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
|
||||
|
||||
// Felix 2.0+ electronics with v4 Hotend
|
||||
#define DEFAULT_Kp 12
|
||||
#define DEFAULT_Ki 0.84
|
||||
#define DEFAULT_Kd 85
|
||||
|
||||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//===========================================================================
|
||||
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
|
||||
//
|
||||
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
|
||||
// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
|
||||
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
|
||||
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
|
||||
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
|
||||
// shouldn't use bed PID until someone else verifies your hardware works.
|
||||
// If this is enabled, find your own PID constants below.
|
||||
#define PIDTEMPBED
|
||||
//
|
||||
//#define BED_LIMIT_SWITCHING
|
||||
|
||||
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||
|
||||
#ifdef PIDTEMPBED
|
||||
// Felix Foil Heater
|
||||
#define DEFAULT_bedKp 103.37
|
||||
#define DEFAULT_bedKi 2.79
|
||||
#define DEFAULT_bedKd 956.94
|
||||
|
||||
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
||||
#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
|
||||
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
|
||||
#define PREVENT_LENGTHY_EXTRUDE
|
||||
|
||||
#define EXTRUDE_MINTEMP 170
|
||||
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
|
||||
|
||||
//===========================================================================
|
||||
//============================= Thermal Runaway Protection ==================
|
||||
//===========================================================================
|
||||
/*
|
||||
This is a feature to protect your printer from burn up in flames if it has
|
||||
a thermistor coming off place (this happened to a friend of mine recently and
|
||||
motivated me writing this feature).
|
||||
|
||||
The issue: If a thermistor come off, it will read a lower temperature than actual.
|
||||
The system will turn the heater on forever, burning up the filament and anything
|
||||
else around.
|
||||
|
||||
After the temperature reaches the target for the first time, this feature will
|
||||
start measuring for how long the current temperature stays below the target
|
||||
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
|
||||
|
||||
If it stays longer than _PERIOD, it means the thermistor temperature
|
||||
cannot catch up with the target, so something *may be* wrong. Then, to be on the
|
||||
safe side, the system will he halt.
|
||||
|
||||
Bear in mind the count down will just start AFTER the first time the
|
||||
thermistor temperature is over the target, so you will have no problem if
|
||||
your extruder heater takes 2 minutes to hit the target on heating.
|
||||
|
||||
*/
|
||||
// If you want to enable this feature for all your extruder heaters,
|
||||
// uncomment the 2 defines below:
|
||||
|
||||
// Parameters for all extruder heaters
|
||||
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 60 //in seconds
|
||||
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 5 // in degree Celsius
|
||||
|
||||
// If you want to enable this feature for your bed heater,
|
||||
// uncomment the 2 defines below:
|
||||
|
||||
// Parameters for the bed heater
|
||||
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 30 //in seconds
|
||||
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 5// in degree Celsius
|
||||
|
||||
|
||||
//===========================================================================
|
||||
//============================= Mechanical Settings =========================
|
||||
//===========================================================================
|
||||
|
||||
// Uncomment the following line 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
|
||||
|
||||
#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
|
||||
|
||||
#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 = 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 = 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.
|
||||
#define DISABLE_MAX_ENDSTOPS
|
||||
//#define DISABLE_MIN_ENDSTOPS
|
||||
|
||||
// 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
|
||||
#define Z_ENABLE_ON 0
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
#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 true // 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 true // 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
|
||||
|
||||
// ENDSTOP SETTINGS:
|
||||
// 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
|
||||
|
||||
#define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
|
||||
#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 255
|
||||
#define X_MIN_POS 0
|
||||
#define Y_MAX_POS 205
|
||||
#define Y_MIN_POS 0
|
||||
#define Z_MAX_POS 235
|
||||
#define Z_MIN_POS 0
|
||||
|
||||
#define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)
|
||||
#define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
|
||||
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
|
||||
|
||||
|
||||
//===========================================================================
|
||||
//============================= Bed Auto Leveling ===========================
|
||||
//===========================================================================
|
||||
|
||||
//#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
|
||||
|
||||
#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
|
||||
|
||||
// Use one of these defines to specify the origin
|
||||
// for a topographical map to be printed for your bed.
|
||||
enum { OriginBackLeft, OriginFrontLeft, OriginBackRight, OriginFrontRight };
|
||||
#define TOPO_ORIGIN OriginFrontLeft
|
||||
|
||||
// set 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
|
||||
|
||||
// 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 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
|
||||
|
||||
#define ABL_PROBE_PT_1_X 15
|
||||
#define ABL_PROBE_PT_1_Y 180
|
||||
#define ABL_PROBE_PT_2_X 15
|
||||
#define ABL_PROBE_PT_2_Y 20
|
||||
#define ABL_PROBE_PT_3_X 170
|
||||
#define ABL_PROBE_PT_3_Y 20
|
||||
|
||||
#endif // AUTO_BED_LEVELING_GRID
|
||||
|
||||
|
||||
// these are the 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 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
|
||||
|
||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min
|
||||
|
||||
#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.
|
||||
// You MUST HAVE the SERVO_ENDSTOPS defined to use here a value higher than zero otherwise your code will not compile.
|
||||
|
||||
// #define PROBE_SERVO_DEACTIVATION_DELAY 300
|
||||
|
||||
|
||||
//If you have enabled the Bed Auto Leveling and are using the same Z Probe for Z Homing,
|
||||
//it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
||||
|
||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with probe outside the bed area.
|
||||
// When defined, it will:
|
||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled
|
||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing
|
||||
// - Position the probe in a defined XY point before Z Homing when homing all axis (G28)
|
||||
// - Block Z homing only when the probe is outside bed area.
|
||||
|
||||
#ifdef Z_SAFE_HOMING
|
||||
|
||||
#define Z_SAFE_HOMING_X_POINT (X_MAX_LENGTH/2) // X point for Z homing when homing all axis (G28)
|
||||
#define Z_SAFE_HOMING_Y_POINT (Y_MAX_LENGTH/2) // Y point for Z homing when homing all axis (G28)
|
||||
|
||||
#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
|
||||
|
||||
|
||||
// The position of the homing switches
|
||||
//#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:
|
||||
// For deltabots this means top and center of the Cartesian print volume.
|
||||
#define MANUAL_X_HOME_POS 0
|
||||
#define MANUAL_Y_HOME_POS 0
|
||||
#define MANUAL_Z_HOME_POS 0
|
||||
//#define MANUAL_Z_HOME_POS 402 // For delta: Distance between nozzle and print surface after homing.
|
||||
|
||||
//// MOVEMENT SETTINGS
|
||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||
#define HOMING_FEEDRATE {50*60, 50*60, 4*60, 0} // set the homing speeds (mm/min)
|
||||
|
||||
// default settings
|
||||
|
||||
// default steps per unit for Felix 2.0/3.0: 0.00249mm x/y rounding error with 3mm pitch HTD belt and 14 tooth pulleys. 0 z error.
|
||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {76.190476, 76.190476, 1600, 164}
|
||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
|
||||
#define DEFAULT_MAX_ACCELERATION {5000,5000,100,80000} // 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 1750 //1500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||
#define DEFAULT_RETRACT_ACCELERATION 5000 // X, Y, Z and E max acceleration in mm/s^2 for r 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).
|
||||
// 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
|
||||
|
||||
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
|
||||
#define DEFAULT_XYJERK 10 // (mm/sec)
|
||||
#define DEFAULT_ZJERK 0.3 //0.4 // (mm/sec)
|
||||
#define DEFAULT_EJERK 5.0 // (mm/sec)
|
||||
|
||||
|
||||
//=============================================================================
|
||||
//============================= Additional Features ===========================
|
||||
//=============================================================================
|
||||
|
||||
// Custom M code points
|
||||
#define CUSTOM_M_CODES
|
||||
#ifdef CUSTOM_M_CODES
|
||||
#define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
|
||||
#define Z_PROBE_OFFSET_RANGE_MIN -15
|
||||
#define Z_PROBE_OFFSET_RANGE_MAX -5
|
||||
#endif
|
||||
|
||||
|
||||
// EEPROM
|
||||
// The microcontroller can store settings in the EEPROM, e.g. max velocity...
|
||||
// M500 - stores parameters in EEPROM
|
||||
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
||||
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
||||
//define this to enable EEPROM support
|
||||
//#define EEPROM_SETTINGS
|
||||
//to disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
|
||||
// please keep turned on if you can.
|
||||
//#define EEPROM_CHITCHAT
|
||||
|
||||
// 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 ABS_PREHEAT_HOTEND_TEMP 240
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
|
||||
|
||||
//==============================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°"
|
||||
//#define DISPLAY_CHARSET_HD44780_WESTERN // "ÄäÖöÜüß²³°" if you see a '~' instead of a 'arrow_right' at the right of submenuitems - this is the right one.
|
||||
|
||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||
//#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 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
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
//#define PANEL_ONE
|
||||
|
||||
// The MaKr3d Makr-Panel with graphic controller and SD support
|
||||
// http://reprap.org/wiki/MaKr3d_MaKrPanel
|
||||
//#define MAKRPANEL
|
||||
|
||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||
// http://panucatt.com
|
||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
||||
//#define VIKI2
|
||||
//#define miniVIKI
|
||||
|
||||
// The RepRapDiscount Smart Controller (white PCB)
|
||||
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
|
||||
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||
|
||||
// The GADGETS3D G3D LCD/SD Controller (blue PCB)
|
||||
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
|
||||
//#define G3D_PANEL
|
||||
|
||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||
//
|
||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||
|
||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
|
||||
//#define REPRAPWORLD_KEYPAD
|
||||
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // how much should be moved when a key is pressed, eg 10.0 means 10mm per click
|
||||
|
||||
// The Elefu RA Board Control Panel
|
||||
// http://www.elefu.com/index.php?route=product/product&product_id=53
|
||||
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
||||
//#define RA_CONTROL_PANEL
|
||||
|
||||
//automatic expansion
|
||||
#if defined (MAKRPANEL)
|
||||
#define DOGLCD
|
||||
#define SDSUPPORT
|
||||
#define ULTIPANEL
|
||||
#define NEWPANEL
|
||||
#define DEFAULT_LCD_CONTRAST 17
|
||||
#endif
|
||||
|
||||
#if defined(miniVIKI) || defined(VIKI2)
|
||||
#define ULTRA_LCD //general LCD support, also 16x2
|
||||
#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||
#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
|
||||
#ifdef miniVIKI
|
||||
#define DEFAULT_LCD_CONTRAST 95
|
||||
#else
|
||||
#define DEFAULT_LCD_CONTRAST 40
|
||||
#endif
|
||||
|
||||
#define ENCODER_PULSES_PER_STEP 4
|
||||
#define ENCODER_STEPS_PER_MENU_ITEM 1
|
||||
#endif
|
||||
|
||||
#if defined (PANEL_ONE)
|
||||
#define SDSUPPORT
|
||||
#define ULTIMAKERCONTROLLER
|
||||
#endif
|
||||
|
||||
#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
|
||||
#define DOGLCD
|
||||
#define U8GLIB_ST7920
|
||||
#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||
#endif
|
||||
|
||||
#if defined(ULTIMAKERCONTROLLER) || defined(REPRAP_DISCOUNT_SMART_CONTROLLER) || defined(G3D_PANEL)
|
||||
#define ULTIPANEL
|
||||
#define NEWPANEL
|
||||
#endif
|
||||
|
||||
#if defined(REPRAPWORLD_KEYPAD)
|
||||
#define NEWPANEL
|
||||
#define ULTIPANEL
|
||||
#endif
|
||||
#if defined(RA_CONTROL_PANEL)
|
||||
#define ULTIPANEL
|
||||
#define NEWPANEL
|
||||
#define LCD_I2C_TYPE_PCA8574
|
||||
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
|
||||
#endif
|
||||
|
||||
//I2C PANELS
|
||||
|
||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||
#ifdef LCD_I2C_SAINSMART_YWROBOT
|
||||
// This uses the LiquidCrystal_I2C library ( https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home )
|
||||
// Make sure it is placed in the Arduino libraries directory.
|
||||
#define LCD_I2C_TYPE_PCF8575
|
||||
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
|
||||
#define NEWPANEL
|
||||
#define ULTIPANEL
|
||||
#endif
|
||||
|
||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||
//#define LCD_I2C_PANELOLU2
|
||||
#ifdef LCD_I2C_PANELOLU2
|
||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
|
||||
// (v1.2.3 no longer requires you to define PANELOLU in the LiquidTWI2.h library header file)
|
||||
// Note: The PANELOLU2 encoder click input can either be directly connected to a pin
|
||||
// (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1).
|
||||
#define LCD_I2C_TYPE_MCP23017
|
||||
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
|
||||
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD
|
||||
#define NEWPANEL
|
||||
#define ULTIPANEL
|
||||
|
||||
#ifndef ENCODER_PULSES_PER_STEP
|
||||
#define ENCODER_PULSES_PER_STEP 4
|
||||
#endif
|
||||
|
||||
#ifndef ENCODER_STEPS_PER_MENU_ITEM
|
||||
#define ENCODER_STEPS_PER_MENU_ITEM 1
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef LCD_USE_I2C_BUZZER
|
||||
#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
||||
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
// Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
|
||||
//#define LCD_I2C_VIKI
|
||||
#ifdef LCD_I2C_VIKI
|
||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
|
||||
// Note: The pause/stop/resume LCD button pin should be connected to the Arduino
|
||||
// BTN_ENC pin (or set BTN_ENC to -1 if not used)
|
||||
#define LCD_I2C_TYPE_MCP23017
|
||||
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
|
||||
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later)
|
||||
#define NEWPANEL
|
||||
#define ULTIPANEL
|
||||
#endif
|
||||
|
||||
// Shift register panels
|
||||
// ---------------------
|
||||
// 2 wire Non-latching LCD SR from:
|
||||
// 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
|
||||
|
||||
|
||||
#ifdef ULTIPANEL
|
||||
#define NEWPANEL //enable this if you have a click-encoder panel
|
||||
#define SDSUPPORT
|
||||
#define ULTRA_LCD
|
||||
#ifdef DOGLCD // Change number of lines to match the DOG graphic display
|
||||
#define LCD_WIDTH 22
|
||||
#define LCD_HEIGHT 5
|
||||
#else
|
||||
#define LCD_WIDTH 20
|
||||
#define LCD_HEIGHT 4
|
||||
#endif
|
||||
#else //no panel but just LCD
|
||||
#ifdef ULTRA_LCD
|
||||
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
|
||||
#define LCD_WIDTH 22
|
||||
#define LCD_HEIGHT 5
|
||||
#else
|
||||
#define LCD_WIDTH 16
|
||||
#define LCD_HEIGHT 2
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// default LCD contrast for dogm-like LCD displays
|
||||
#ifdef DOGLCD
|
||||
# ifndef DEFAULT_LCD_CONTRAST
|
||||
# define DEFAULT_LCD_CONTRAST 32
|
||||
# endif
|
||||
#endif
|
||||
|
||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||
#define FAST_PWM_FAN
|
||||
|
||||
// Temperature status LEDs that display the hotend and bet temperature.
|
||||
// If all hotends and bed temperature and temperature setpoint are < 54C then the BLUE led is on.
|
||||
// Otherwise the RED led is on. There is 1C hysteresis.
|
||||
//#define TEMP_STAT_LEDS
|
||||
|
||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||
// which is not as annoying as with the hardware PWM. On the other hand, if this frequency
|
||||
// is too low, you should also increment SOFT_PWM_SCALE.
|
||||
//#define FAN_SOFT_PWM
|
||||
|
||||
// Incrementing this by 1 will double the software PWM frequency,
|
||||
// affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
|
||||
// However, control resolution will be halved for each increment;
|
||||
// at zero value, there are 128 effective control positions.
|
||||
#define SOFT_PWM_SCALE 0
|
||||
|
||||
// M240 Triggers a camera by emulating a Canon RC-1 Remote
|
||||
// Data from: http://www.doc-diy.net/photo/rc-1_hacked/
|
||||
// #define PHOTOGRAPH_PIN 23
|
||||
|
||||
// SF send wrong arc g-codes when using Arc Point as fillet procedure
|
||||
//#define SF_ARC_FIX
|
||||
|
||||
// Support for the BariCUDA Paste Extruder.
|
||||
//#define BARICUDA
|
||||
|
||||
//define BlinkM/CyzRgb Support
|
||||
//#define BLINKM
|
||||
|
||||
/*********************************************************************\
|
||||
* R/C SERVO support
|
||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||
**********************************************************************/
|
||||
|
||||
// Number of servos
|
||||
//
|
||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
||||
// set it manually if you have more servos than extruders and wish to manually control some
|
||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
||||
// If unsure, leave commented / disabled
|
||||
//
|
||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||
|
||||
// Servo Endstops
|
||||
//
|
||||
// This allows for servo actuated endstops, primary usage is for the Z Axis to eliminate calibration or bed height changes.
|
||||
// Use M206 command to correct for switch height offset to actual nozzle height. Store that setting with M500.
|
||||
//
|
||||
//#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1
|
||||
//#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 70,0} // X,Y,Z Axis Extend and Retract angles
|
||||
|
||||
/**********************************************************************\
|
||||
* Support for a filament diameter sensor
|
||||
* Also allows adjustment of diameter at print time (vs at slicing)
|
||||
* Single extruder only at this point (extruder 0)
|
||||
*
|
||||
* Motherboards
|
||||
* 34 - RAMPS1.4 - uses Analog input 5 on the AUX2 connector
|
||||
* 81 - Printrboard - Uses Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||
* 301 - Rambo - uses Analog input 3
|
||||
* Note may require analog pins to be defined for different motherboards
|
||||
**********************************************************************/
|
||||
// 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 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)
|
||||
|
||||
//defines used in the code
|
||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||
|
||||
//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status. Status will appear for 5 sec.
|
||||
//#define FILAMENT_LCD_DISPLAY
|
||||
|
||||
|
||||
#include "Configuration_adv.h"
|
||||
#include "thermistortables.h"
|
||||
|
||||
#endif //__CONFIGURATION_H
|
541
Marlin/example_configurations/Felix/Configuration_adv.h
Normal file
|
@ -0,0 +1,541 @@
|
|||
#ifndef CONFIGURATION_ADV_H
|
||||
#define CONFIGURATION_ADV_H
|
||||
|
||||
//===========================================================================
|
||||
//=============================Thermal Settings ============================
|
||||
//===========================================================================
|
||||
|
||||
#ifdef BED_LIMIT_SWITCHING
|
||||
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||
#endif
|
||||
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
|
||||
|
||||
//// Heating sanity check:
|
||||
// This waits for the watch period in milliseconds whenever an M104 or M109 increases the target temperature
|
||||
// If the temperature has not increased at the end of that period, the target temperature is set to zero.
|
||||
// It can be reset with another M104/M109. This check is also only triggered if the target temperature and the current temperature
|
||||
// differ by at least 2x WATCH_TEMP_INCREASE
|
||||
//#define WATCH_TEMP_PERIOD 40000 //40 seconds
|
||||
//#define WATCH_TEMP_INCREASE 10 //Heat up at least 10 degree in 20 seconds
|
||||
|
||||
#ifdef PIDTEMP
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
#define PID_ADD_EXTRUSION_RATE
|
||||
#ifdef PID_ADD_EXTRUSION_RATE
|
||||
#define DEFAULT_Kc (1) //heating power=Kc*(e_speed)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
|
||||
//The maximum buffered steps/sec of the extruder motor are called "se".
|
||||
//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
|
||||
// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
|
||||
// you exit the value by any M109 without F*
|
||||
// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
|
||||
// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||
#define AUTOTEMP
|
||||
#ifdef AUTOTEMP
|
||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||
#endif
|
||||
|
||||
//Show Temperature ADC value
|
||||
//The M105 command return, besides traditional information, the ADC value read from temperature sensors.
|
||||
//#define SHOW_TEMP_ADC_VALUES
|
||||
|
||||
// extruder run-out prevention.
|
||||
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
|
||||
//#define EXTRUDER_RUNOUT_PREVENT
|
||||
#define EXTRUDER_RUNOUT_MINTEMP 190
|
||||
#define EXTRUDER_RUNOUT_SECONDS 30.
|
||||
#define EXTRUDER_RUNOUT_ESTEPS 14. //mm filament
|
||||
#define EXTRUDER_RUNOUT_SPEED 1500. //extrusion speed
|
||||
#define EXTRUDER_RUNOUT_EXTRUDE 100
|
||||
|
||||
//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
|
||||
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
|
||||
#define TEMP_SENSOR_AD595_OFFSET 0.0
|
||||
#define TEMP_SENSOR_AD595_GAIN 1.0
|
||||
|
||||
//This is for controlling a fan to cool down the stepper drivers
|
||||
//it will turn on when any driver is enabled
|
||||
//and turn off after the set amount of seconds from last driver being disabled again
|
||||
#define CONTROLLERFAN_PIN -1 //Pin used for the fan to cool controller (-1 to disable)
|
||||
#define CONTROLLERFAN_SECS 60 //How many seconds, after all motors were disabled, the fan should run
|
||||
#define CONTROLLERFAN_SPEED 255 // == full speed
|
||||
|
||||
// When first starting the main fan, run it at full speed for the
|
||||
// given number of milliseconds. This gets the fan spinning reliably
|
||||
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
|
||||
//#define FAN_KICKSTART_TIME 100
|
||||
|
||||
// Extruder cooling fans
|
||||
// Configure fan pin outputs to automatically turn on/off when the associated
|
||||
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
|
||||
// Multiple extruders can be assigned to the same pin in which case
|
||||
// the fan will turn on when any selected extruder is above the threshold.
|
||||
#define EXTRUDER_0_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_1_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_2_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_3_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
|
||||
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
|
||||
|
||||
|
||||
//===========================================================================
|
||||
//=============================Mechanical Settings===========================
|
||||
//===========================================================================
|
||||
|
||||
#define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing
|
||||
|
||||
|
||||
//// AUTOSET LOCATIONS OF LIMIT SWITCHES
|
||||
//// Added by ZetaPhoenix 09-15-2012
|
||||
#ifdef MANUAL_HOME_POSITIONS // Use manual limit switch locations
|
||||
#define X_HOME_POS MANUAL_X_HOME_POS
|
||||
#define Y_HOME_POS MANUAL_Y_HOME_POS
|
||||
#define Z_HOME_POS MANUAL_Z_HOME_POS
|
||||
#else //Set min/max homing switch positions based upon homing direction and min/max travel limits
|
||||
//X axis
|
||||
#if X_HOME_DIR == -1
|
||||
#ifdef BED_CENTER_AT_0_0
|
||||
#define X_HOME_POS X_MAX_LENGTH * -0.5
|
||||
#else
|
||||
#define X_HOME_POS X_MIN_POS
|
||||
#endif //BED_CENTER_AT_0_0
|
||||
#else
|
||||
#ifdef BED_CENTER_AT_0_0
|
||||
#define X_HOME_POS X_MAX_LENGTH * 0.5
|
||||
#else
|
||||
#define X_HOME_POS X_MAX_POS
|
||||
#endif //BED_CENTER_AT_0_0
|
||||
#endif //X_HOME_DIR == -1
|
||||
|
||||
//Y axis
|
||||
#if Y_HOME_DIR == -1
|
||||
#ifdef BED_CENTER_AT_0_0
|
||||
#define Y_HOME_POS Y_MAX_LENGTH * -0.5
|
||||
#else
|
||||
#define Y_HOME_POS Y_MIN_POS
|
||||
#endif //BED_CENTER_AT_0_0
|
||||
#else
|
||||
#ifdef BED_CENTER_AT_0_0
|
||||
#define Y_HOME_POS Y_MAX_LENGTH * 0.5
|
||||
#else
|
||||
#define Y_HOME_POS Y_MAX_POS
|
||||
#endif //BED_CENTER_AT_0_0
|
||||
#endif //Y_HOME_DIR == -1
|
||||
|
||||
// Z axis
|
||||
#if Z_HOME_DIR == -1 //BED_CENTER_AT_0_0 not used
|
||||
#define Z_HOME_POS Z_MIN_POS
|
||||
#else
|
||||
#define Z_HOME_POS Z_MAX_POS
|
||||
#endif //Z_HOME_DIR == -1
|
||||
#endif //End auto min/max positions
|
||||
//END AUTOSET LOCATIONS OF LIMIT SWITCHES -ZP
|
||||
|
||||
|
||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||
|
||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
||||
// Uncomment this define to utilize a separate stepper driver for each Z axis motor.
|
||||
// Only a few motherboards support this, like RAMPS, which have dual extruder support (the 2nd, often unused, extruder driver is used
|
||||
// to control the 2nd Z axis stepper motor). The pins are currently only defined for a RAMPS motherboards.
|
||||
// On a RAMPS (or other 5 driver) motherboard, using this feature will limit you to using 1 extruder.
|
||||
//#define Z_DUAL_STEPPER_DRIVERS
|
||||
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
#undef EXTRUDERS
|
||||
#define EXTRUDERS 1
|
||||
#endif
|
||||
|
||||
// Same again but for Y Axis.
|
||||
//#define Y_DUAL_STEPPER_DRIVERS
|
||||
|
||||
// Define if the two Y drives need to rotate in opposite directions
|
||||
#define INVERT_Y2_VS_Y_DIR true
|
||||
|
||||
#ifdef Y_DUAL_STEPPER_DRIVERS
|
||||
#undef EXTRUDERS
|
||||
#define EXTRUDERS 1
|
||||
#endif
|
||||
|
||||
#if defined (Z_DUAL_STEPPER_DRIVERS) && defined (Y_DUAL_STEPPER_DRIVERS)
|
||||
#error "You cannot have dual drivers for both Y and Z"
|
||||
#endif
|
||||
|
||||
// Enable this for dual x-carriage printers.
|
||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
|
||||
// allowing faster printing speeds.
|
||||
//#define DUAL_X_CARRIAGE
|
||||
#ifdef DUAL_X_CARRIAGE
|
||||
// Configuration for second X-carriage
|
||||
// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
|
||||
// the second x-carriage always homes to the maximum endstop.
|
||||
#define X2_MIN_POS 80 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
|
||||
#define X2_MAX_POS 353 // set maximum to the distance between toolheads when both heads are homed
|
||||
#define X2_HOME_DIR 1 // the second X-carriage always homes to the maximum endstop position
|
||||
#define X2_HOME_POS X2_MAX_POS // default home position is the maximum carriage position
|
||||
// However: In this mode the EXTRUDER_OFFSET_X value for the second extruder provides a software
|
||||
// override for X2_HOME_POS. This also allow recalibration of the distance between the two endstops
|
||||
// without modifying the firmware (through the "M218 T1 X???" command).
|
||||
// Remember: you should set the second extruder x-offset to 0 in your slicer.
|
||||
|
||||
// Pins for second x-carriage stepper driver (defined here to avoid further complicating pins.h)
|
||||
#define X2_ENABLE_PIN 29
|
||||
#define X2_STEP_PIN 25
|
||||
#define X2_DIR_PIN 23
|
||||
|
||||
// There are a few selectable movement modes for dual x-carriages using M605 S<mode>
|
||||
// Mode 0: Full control. The slicer has full control over both x-carriages and can achieve optimal travel results
|
||||
// as long as it supports dual x-carriages. (M605 S0)
|
||||
// Mode 1: Auto-park mode. The firmware will automatically park and unpark the x-carriages on tool changes so
|
||||
// that additional slicer support is not required. (M605 S1)
|
||||
// Mode 2: Duplication mode. The firmware will transparently make the second x-carriage and extruder copy all
|
||||
// actions of the first x-carriage. This allows the printer to print 2 arbitrary items at
|
||||
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
|
||||
|
||||
// This is the default power-up mode which can be later using M605.
|
||||
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
|
||||
|
||||
// Default settings in "Auto-park Mode"
|
||||
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
|
||||
#define TOOLCHANGE_UNPARK_ZLIFT 1 // the distance to raise Z axis when unparking an extruder
|
||||
|
||||
// Default x offset in duplication mode (typically set to half print bed width)
|
||||
#define DEFAULT_DUPLICATION_X_OFFSET 100
|
||||
|
||||
#endif //DUAL_X_CARRIAGE
|
||||
|
||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
||||
#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}
|
||||
#ifdef CONFIG_STEPPERS_TOSHIBA
|
||||
#define MAX_STEP_FREQUENCY 10000 // Max step frequency for Toshiba Stepper Controllers
|
||||
#else
|
||||
#define MAX_STEP_FREQUENCY 40000 // Max step frequency for Ultimaker (5000 pps / half step)
|
||||
#endif
|
||||
//By default pololu step drivers require an active high signal. However, some high power drivers require an active low signal as step.
|
||||
#define INVERT_X_STEP_PIN false
|
||||
#define INVERT_Y_STEP_PIN false
|
||||
#define INVERT_Z_STEP_PIN false
|
||||
#define INVERT_E_STEP_PIN false
|
||||
|
||||
//default stepper release if idle. Set to 0 to deactivate.
|
||||
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
||||
|
||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||
|
||||
// Feedrates for manual moves along X, Y, Z, E from panel
|
||||
#ifdef ULTIPANEL
|
||||
#define MANUAL_FEEDRATE {50*60, 50*60, 4*60, 60} // set the speeds for manual moves (mm/min)
|
||||
#endif
|
||||
|
||||
//Comment to disable setting feedrate multiplier via encoder
|
||||
#ifdef ULTIPANEL
|
||||
#define ULTIPANEL_FEEDMULTIPLY
|
||||
#endif
|
||||
|
||||
// minimum time in microseconds that a movement needs to take if the buffer is emptied.
|
||||
#define DEFAULT_MINSEGMENTTIME 20000
|
||||
|
||||
// If defined the movements slow down when the look ahead buffer is only half full
|
||||
#define SLOWDOWN
|
||||
|
||||
// Frequency limit
|
||||
// See nophead's blog for more info
|
||||
// Not working O
|
||||
//#define XY_FREQUENCY_LIMIT 15
|
||||
|
||||
// Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
|
||||
// of the buffer and all stops. This should not be much greater than zero and should only be changed
|
||||
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
|
||||
#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
|
||||
|
||||
// MS1 MS2 Stepper Driver Microstepping mode table
|
||||
#define MICROSTEP1 LOW,LOW
|
||||
#define MICROSTEP2 HIGH,LOW
|
||||
#define MICROSTEP4 LOW,HIGH
|
||||
#define MICROSTEP8 HIGH,HIGH
|
||||
#define MICROSTEP16 HIGH,HIGH
|
||||
|
||||
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
|
||||
#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
|
||||
|
||||
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||
|
||||
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
||||
//#define DIGIPOT_I2C
|
||||
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
||||
#define DIGIPOT_I2C_NUM_CHANNELS 8
|
||||
// actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||
#define DIGIPOT_I2C_MOTOR_CURRENTS {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0}
|
||||
|
||||
//===========================================================================
|
||||
//=============================Additional Features===========================
|
||||
//===========================================================================
|
||||
|
||||
#define ENCODER_RATE_MULTIPLIER // If defined, certain menu edit operations automatically multiply the steps when the encoder is moved quickly
|
||||
#define ENCODER_10X_STEPS_PER_SEC 75 // If the encoder steps per sec exceed this value, multiple the steps moved by ten to quickly advance the value
|
||||
#define ENCODER_100X_STEPS_PER_SEC 160 // If the encoder steps per sec exceed this value, multiple the steps moved by 100 to really quickly advance the value
|
||||
//#define ENCODER_RATE_MULTIPLIER_DEBUG // If defined, output the encoder steps per second value
|
||||
|
||||
//#define CHDK 4 //Pin for triggering CHDK to take a picture see how to use it here http://captain-slow.dk/2014/03/09/3d-printing-timelapses/
|
||||
#define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
|
||||
|
||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
||||
#define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
|
||||
|
||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
||||
// if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
|
||||
// using:
|
||||
//#define MENU_ADDAUTOSTART
|
||||
|
||||
// Show a progress bar on HD44780 LCDs for SD printing
|
||||
//#define LCD_PROGRESS_BAR
|
||||
|
||||
#ifdef LCD_PROGRESS_BAR
|
||||
// Amount of time (ms) to show the bar
|
||||
#define PROGRESS_BAR_BAR_TIME 2000
|
||||
// Amount of time (ms) to show the status message
|
||||
#define PROGRESS_BAR_MSG_TIME 3000
|
||||
// Amount of time (ms) to retain the status message (0=forever)
|
||||
#define PROGRESS_MSG_EXPIRE 0
|
||||
// Enable this to show messages for MSG_TIME then hide them
|
||||
//#define PROGRESS_MSG_ONCE
|
||||
#ifdef DOGLCD
|
||||
#warning LCD_PROGRESS_BAR does not apply to graphical displays at this time.
|
||||
#endif
|
||||
#ifdef FILAMENT_LCD_DISPLAY
|
||||
#error LCD_PROGRESS_BAR and FILAMENT_LCD_DISPLAY are not fully compatible. Comment out this line to use both.
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
||||
//#define USE_WATCHDOG
|
||||
|
||||
#ifdef USE_WATCHDOG
|
||||
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||
// However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
|
||||
//#define WATCHDOG_RESET_MANUAL
|
||||
#endif
|
||||
|
||||
// Enable the option to stop SD printing when hitting and endstops, needs to be enabled from the LCD menu when this option is enabled.
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
// Babystepping enables the user to control the axis in tiny amounts, independently from the normal printing process
|
||||
// it can e.g. be used to change z-positions in the print startup phase in real-time
|
||||
// does not respect endstops!
|
||||
//#define BABYSTEPPING
|
||||
#ifdef BABYSTEPPING
|
||||
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
||||
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
||||
#define BABYSTEP_Z_MULTIPLICATOR 2 //faster z movements
|
||||
|
||||
#ifdef COREXY
|
||||
#error BABYSTEPPING not implemented for COREXY yet.
|
||||
#endif
|
||||
|
||||
#ifdef DELTA
|
||||
#ifdef BABYSTEP_XY
|
||||
#error BABYSTEPPING only implemented for Z axis on deltabots.
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// extruder advance constant (s2/mm3)
|
||||
//
|
||||
// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
|
||||
//
|
||||
// Hooke's law says: force = k * distance
|
||||
// Bernoulli's principle says: v ^ 2 / 2 + g . h + pressure / density = constant
|
||||
// so: v ^ 2 is proportional to number of steps we advance the extruder
|
||||
//#define ADVANCE
|
||||
|
||||
#ifdef ADVANCE
|
||||
#define EXTRUDER_ADVANCE_K .0
|
||||
|
||||
#define D_FILAMENT 2.85
|
||||
#define STEPS_MM_E 836
|
||||
#define EXTRUSION_AREA (0.25 * D_FILAMENT * D_FILAMENT * 3.14159)
|
||||
#define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS]/ EXTRUSION_AREA)
|
||||
|
||||
#endif // ADVANCE
|
||||
|
||||
// Arc interpretation settings:
|
||||
#define MM_PER_ARC_SEGMENT 1
|
||||
#define N_ARC_CORRECTION 25
|
||||
|
||||
const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
||||
|
||||
// If you are using a RAMPS board or cheap E-bay purchased boards that do not detect when an SD card is inserted
|
||||
// You can get round this by connecting a push button or single throw switch to the pin defined as SDCARDCARDDETECT
|
||||
// in the pins.h file. When using a push button pulling the pin to ground this will need inverted. This setting should
|
||||
// be commented out otherwise
|
||||
#define SDCARDDETECTINVERTED
|
||||
|
||||
//#ifdef ULTIPANEL
|
||||
// #undef SDCARDDETECTINVERTED
|
||||
//#endif
|
||||
|
||||
// Power Signal Control Definitions
|
||||
// By default use ATX definition
|
||||
#ifndef POWER_SUPPLY
|
||||
#define POWER_SUPPLY 1
|
||||
#endif
|
||||
// 1 = ATX
|
||||
#if (POWER_SUPPLY == 1)
|
||||
#define PS_ON_AWAKE LOW
|
||||
#define PS_ON_ASLEEP HIGH
|
||||
#endif
|
||||
// 2 = X-Box 360 203W
|
||||
#if (POWER_SUPPLY == 2)
|
||||
#define PS_ON_AWAKE HIGH
|
||||
#define PS_ON_ASLEEP LOW
|
||||
#endif
|
||||
|
||||
// Control heater 0 and heater 1 in parallel.
|
||||
//#define HEATERS_PARALLEL
|
||||
|
||||
//===========================================================================
|
||||
//=============================Buffers ============================
|
||||
//===========================================================================
|
||||
|
||||
// The number of linear motions that can be in the plan at any give time.
|
||||
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
|
||||
#if defined SDSUPPORT
|
||||
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
|
||||
#else
|
||||
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
|
||||
#endif
|
||||
|
||||
|
||||
//The ASCII buffer for receiving from the serial:
|
||||
#define MAX_CMD_SIZE 96
|
||||
#define BUFSIZE 4
|
||||
|
||||
|
||||
// Firmware based and LCD controlled retract
|
||||
// M207 and M208 can be used to define parameters for the retraction.
|
||||
// The retraction can be called by the slicer using G10 and G11
|
||||
// until then, intended retractions can be detected by moves that only extrude and the direction.
|
||||
// the moves are than replaced by the firmware controlled ones.
|
||||
|
||||
// #define FWRETRACT //ONLY PARTIALLY TESTED
|
||||
#ifdef FWRETRACT
|
||||
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
|
||||
#define RETRACT_LENGTH 3 //default retract length (positive mm)
|
||||
#define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change
|
||||
#define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s)
|
||||
#define RETRACT_ZLIFT 0 //default retract Z-lift
|
||||
#define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering)
|
||||
#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change)
|
||||
#define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s)
|
||||
#endif
|
||||
|
||||
//adds support for experimental filament exchange support M600; requires display
|
||||
#ifdef ULTIPANEL
|
||||
#define FILAMENTCHANGEENABLE
|
||||
#ifdef FILAMENTCHANGEENABLE
|
||||
#define FILAMENTCHANGE_XPOS 3
|
||||
#define FILAMENTCHANGE_YPOS 3
|
||||
#define FILAMENTCHANGE_ZADD 10
|
||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||
#define FILAMENTCHANGE_FINALRETRACT -100
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef FILAMENTCHANGEENABLE
|
||||
#ifdef EXTRUDER_RUNOUT_PREVENT
|
||||
#error EXTRUDER_RUNOUT_PREVENT currently incompatible with FILAMENTCHANGE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//===========================================================================
|
||||
//============================= Define Defines ============================
|
||||
//===========================================================================
|
||||
|
||||
#if defined (ENABLE_AUTO_BED_LEVELING) && defined (DELTA)
|
||||
#error "Bed Auto Leveling is still not compatible with Delta Kinematics."
|
||||
#endif
|
||||
|
||||
#if EXTRUDERS > 1 && defined TEMP_SENSOR_1_AS_REDUNDANT
|
||||
#error "You cannot use TEMP_SENSOR_1_AS_REDUNDANT if EXTRUDERS > 1"
|
||||
#endif
|
||||
|
||||
#if EXTRUDERS > 1 && defined HEATERS_PARALLEL
|
||||
#error "You cannot use HEATERS_PARALLEL if EXTRUDERS > 1"
|
||||
#endif
|
||||
|
||||
#if TEMP_SENSOR_0 > 0
|
||||
#define THERMISTORHEATER_0 TEMP_SENSOR_0
|
||||
#define HEATER_0_USES_THERMISTOR
|
||||
#endif
|
||||
#if TEMP_SENSOR_1 > 0
|
||||
#define THERMISTORHEATER_1 TEMP_SENSOR_1
|
||||
#define HEATER_1_USES_THERMISTOR
|
||||
#endif
|
||||
#if TEMP_SENSOR_2 > 0
|
||||
#define THERMISTORHEATER_2 TEMP_SENSOR_2
|
||||
#define HEATER_2_USES_THERMISTOR
|
||||
#endif
|
||||
#if TEMP_SENSOR_3 > 0
|
||||
#define THERMISTORHEATER_3 TEMP_SENSOR_3
|
||||
#define HEATER_3_USES_THERMISTOR
|
||||
#endif
|
||||
#if TEMP_SENSOR_BED > 0
|
||||
#define THERMISTORBED TEMP_SENSOR_BED
|
||||
#define BED_USES_THERMISTOR
|
||||
#endif
|
||||
#if TEMP_SENSOR_0 == -1
|
||||
#define HEATER_0_USES_AD595
|
||||
#endif
|
||||
#if TEMP_SENSOR_1 == -1
|
||||
#define HEATER_1_USES_AD595
|
||||
#endif
|
||||
#if TEMP_SENSOR_2 == -1
|
||||
#define HEATER_2_USES_AD595
|
||||
#endif
|
||||
#if TEMP_SENSOR_3 == -1
|
||||
#define HEATER_3_USES_AD595
|
||||
#endif
|
||||
#if TEMP_SENSOR_BED == -1
|
||||
#define BED_USES_AD595
|
||||
#endif
|
||||
#if TEMP_SENSOR_0 == -2
|
||||
#define HEATER_0_USES_MAX6675
|
||||
#endif
|
||||
#if TEMP_SENSOR_0 == 0
|
||||
#undef HEATER_0_MINTEMP
|
||||
#undef HEATER_0_MAXTEMP
|
||||
#endif
|
||||
#if TEMP_SENSOR_1 == 0
|
||||
#undef HEATER_1_MINTEMP
|
||||
#undef HEATER_1_MAXTEMP
|
||||
#endif
|
||||
#if TEMP_SENSOR_2 == 0
|
||||
#undef HEATER_2_MINTEMP
|
||||
#undef HEATER_2_MAXTEMP
|
||||
#endif
|
||||
#if TEMP_SENSOR_3 == 0
|
||||
#undef HEATER_3_MINTEMP
|
||||
#undef HEATER_3_MAXTEMP
|
||||
#endif
|
||||
#if TEMP_SENSOR_BED == 0
|
||||
#undef BED_MINTEMP
|
||||
#undef BED_MAXTEMP
|
||||
#endif
|
||||
|
||||
|
||||
#endif //__CONFIGURATION_ADV_H
|
60
Marlin/example_configurations/Felix/README.md
Normal file
|
@ -0,0 +1,60 @@
|
|||
# Felix 2.0/3.0 Configuration for Marlin Firmware
|
||||
|
||||
Bringing silky smooth prints to Felix.
|
||||
|
||||
## Build HOWTO
|
||||
|
||||
- Install the latest non-beta Arduino software IDE/toolset: http://www.arduino.cc/en/Main/Software
|
||||
- Download the Marlin firmware
|
||||
- [Latest developement version](https://github.com/MarlinFirmware/Marlin/tree/Development)
|
||||
- [Stable version](https://github.com/MarlinFirmware/Marlin/tree/Development)
|
||||
- In both cases use the "Download Zip" button on the right.
|
||||
|
||||
```
|
||||
cd Marlin/Marlin
|
||||
cp example_configurations/Felix/Configuration_adv.h .
|
||||
```
|
||||
|
||||
The next step depends on your setup:
|
||||
|
||||
### Single Extruder Configuration
|
||||
|
||||
cp example_configurations/Felix/Configuration.h .
|
||||
|
||||
### Dual Extruder Configuration
|
||||
|
||||
cp example_configurations/Felix/Configuration_DUAL.h Configuration.h
|
||||
|
||||
### Compile Firmware
|
||||
|
||||
- Start the Arduino IDE.
|
||||
- Select Tools -> Board -> Arduino Mega 2560
|
||||
- Select the correct serial port in Tools -> Serial Port (usually /dev/ttyUSB0)
|
||||
- Open Marlin.pde or .ino
|
||||
- Click the Verify/Compile button
|
||||
|
||||
### Flash Firmware
|
||||
|
||||
#### Connected directly via USB
|
||||
|
||||
- Click the Upload button. If all goes well the firmware is uploading
|
||||
|
||||
#### Remote update
|
||||
|
||||
Find the latest Arduino build:
|
||||
|
||||
ls -altr /tmp/
|
||||
drwxr-xr-x 5 chrono users 12288 Mar 3 21:41 build6072035599686630843.tmp
|
||||
|
||||
Copy the firmware to your printer host:
|
||||
|
||||
scp /tmp/build6072035599686630843.tmp/Marlin.cpp.hex a.b.c.d:/tmp/
|
||||
|
||||
Connect to your printer host via ssh, stop Octoprint or any other service that may block your USB device and make sure you have avrdude installed, then run:
|
||||
|
||||
avrdude -C/etc/avrdude.conf -v -v -v -patmega2560 -cwiring -P/dev/ttyUSB0 \
|
||||
-b115200 -D -Uflash:w:/tmp/Marlin.cpp.hex:i
|
||||
|
||||
## Acknowledgements
|
||||
|
||||
Mashed together and tested on https://apollo.open-resource.org/mission:resources:picoprint based on collaborative teamwork of @andrewsil1 and @thinkyhead.
|
|
@ -408,12 +408,19 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||
|
||||
#ifdef AUTO_BED_LEVELING_GRID
|
||||
|
||||
// Use one of these defines to specify the origin
|
||||
// for a topographical map to be printed for your bed.
|
||||
enum { OriginBackLeft, OriginFrontLeft, OriginBackRight, OriginFrontRight };
|
||||
#define TOPO_ORIGIN OriginFrontLeft
|
||||
|
||||
// The edges of the rectangle in which to probe
|
||||
#define LEFT_PROBE_BED_POSITION 15
|
||||
#define RIGHT_PROBE_BED_POSITION 170
|
||||
#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
|
||||
// You probably don't need more than 3 (squared=9)
|
||||
#define AUTO_BED_LEVELING_GRID_POINTS 2
|
||||
|
@ -499,8 +506,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).
|
||||
|
|
|
@ -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}
|
||||
|
|
|
@ -413,12 +413,19 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||
|
||||
#ifdef AUTO_BED_LEVELING_GRID
|
||||
|
||||
// Use one of these defines to specify the origin
|
||||
// for a topographical map to be printed for your bed.
|
||||
enum { OriginBackLeft, OriginFrontLeft, OriginBackRight, OriginFrontRight };
|
||||
#define TOPO_ORIGIN OriginFrontLeft
|
||||
|
||||
// The edges of the rectangle in which to probe
|
||||
#define LEFT_PROBE_BED_POSITION 15
|
||||
#define RIGHT_PROBE_BED_POSITION 170
|
||||
#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
|
||||
// You probably don't need more than 3 (squared=9)
|
||||
#define AUTO_BED_LEVELING_GRID_POINTS 2
|
||||
|
@ -504,8 +511,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).
|
||||
|
|
|
@ -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}
|
||||
|
|
|
@ -437,12 +437,19 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||
|
||||
#ifdef AUTO_BED_LEVELING_GRID
|
||||
|
||||
// Use one of these defines to specify the origin
|
||||
// for a topographical map to be printed for your bed.
|
||||
enum { OriginBackLeft, OriginFrontLeft, OriginBackRight, OriginFrontRight };
|
||||
#define TOPO_ORIGIN OriginFrontLeft
|
||||
|
||||
// The edges of the rectangle in which to probe
|
||||
#define LEFT_PROBE_BED_POSITION 15
|
||||
#define RIGHT_PROBE_BED_POSITION 170
|
||||
#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
|
||||
// You probably don't need more than 3 (squared=9)
|
||||
#define AUTO_BED_LEVELING_GRID_POINTS 2
|
||||
|
@ -529,8 +536,11 @@ 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 the extruder 0 hotend (default extruder).
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -407,12 +407,19 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||
|
||||
#ifdef AUTO_BED_LEVELING_GRID
|
||||
|
||||
// Use one of these defines to specify the origin
|
||||
// for a topographical map to be printed for your bed.
|
||||
enum { OriginBackLeft, OriginFrontLeft, OriginBackRight, OriginFrontRight };
|
||||
#define TOPO_ORIGIN OriginFrontLeft
|
||||
|
||||
// The edges of the rectangle in which to probe
|
||||
#define LEFT_PROBE_BED_POSITION 15
|
||||
#define RIGHT_PROBE_BED_POSITION 170
|
||||
#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
|
||||
// You probably don't need more than 3 (squared=9)
|
||||
#define AUTO_BED_LEVELING_GRID_POINTS 2
|
||||
|
@ -498,8 +505,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).
|
||||
|
|
|
@ -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}
|
||||
|
|