123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632 |
- #include "Marlin.h"
- #include "stepper.h"
- #include "planner.h"
- #include "temperature.h"
- #include "ultralcd.h"
- #include "language.h"
- #include "cardreader.h"
- #include "speed_lookuptable.h"
- #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
- #include <SPI.h>
- #endif
- #ifdef TMC2130
- #include "tmc2130.h"
- #endif
- #ifdef FILAMENT_SENSOR
- #include "fsensor.h"
- int fsensor_counter = 0;
- #endif
- #ifdef DEBUG_STACK_MONITOR
- uint16_t SP_min = 0x21FF;
- #endif
- block_t *current_block;
- bool x_min_endstop = false;
- bool x_max_endstop = false;
- bool y_min_endstop = false;
- bool y_max_endstop = false;
- bool z_min_endstop = false;
- bool z_max_endstop = false;
- static unsigned char out_bits;
- static dda_isteps_t
- counter_x,
- counter_y,
- counter_z,
- counter_e;
- volatile dda_usteps_t step_events_completed;
- static int32_t acceleration_time, deceleration_time;
- static uint16_t acc_step_rate;
- static uint8_t step_loops;
- static uint16_t OCR1A_nominal;
- static uint8_t step_loops_nominal;
- volatile long endstops_trigsteps[3]={0,0,0};
- volatile long endstops_stepsTotal,endstops_stepsDone;
- static volatile bool endstop_x_hit=false;
- static volatile bool endstop_y_hit=false;
- static volatile bool endstop_z_hit=false;
- #ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
- bool abort_on_endstop_hit = false;
- #endif
- #ifdef MOTOR_CURRENT_PWM_XY_PIN
- int motor_current_setting[3] = DEFAULT_PWM_MOTOR_CURRENT;
- int motor_current_setting_silent[3] = DEFAULT_PWM_MOTOR_CURRENT;
- int motor_current_setting_loud[3] = DEFAULT_PWM_MOTOR_CURRENT_LOUD;
- #endif
- static bool old_x_min_endstop=false;
- static bool old_x_max_endstop=false;
- static bool old_y_min_endstop=false;
- static bool old_y_max_endstop=false;
- static bool old_z_min_endstop=false;
- static bool old_z_max_endstop=false;
- static bool check_endstops = true;
- static bool check_z_endstop = false;
- static bool z_endstop_invert = false;
- volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0};
- volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1};
- #ifdef LIN_ADVANCE
- static uint16_t nextMainISR = 0;
- static uint16_t eISR_Rate;
-
-
-
- static volatile int16_t e_steps = 0;
-
- static uint8_t estep_loops;
-
-
- static int current_estep_rate;
-
- static int current_adv_steps;
- #define _NEXT_ISR(T) nextMainISR = T
- #else
- #define _NEXT_ISR(T) OCR1A = T
- #endif
- #ifdef DEBUG_STEPPER_TIMER_MISSED
- extern bool stepper_timer_overflow_state;
- extern uint16_t stepper_timer_overflow_last;
- #endif
- #ifndef _NO_ASM
- #define MultiU16X8toH16(intRes, charIn1, intIn2) \
- asm volatile ( \
- "clr r26 \n\t" \
- "mul %A1, %B2 \n\t" \
- "movw %A0, r0 \n\t" \
- "mul %A1, %A2 \n\t" \
- "add %A0, r1 \n\t" \
- "adc %B0, r26 \n\t" \
- "lsr r0 \n\t" \
- "adc %A0, r26 \n\t" \
- "adc %B0, r26 \n\t" \
- "clr r1 \n\t" \
- : \
- "=&r" (intRes) \
- : \
- "d" (charIn1), \
- "d" (intIn2) \
- : \
- "r26" \
- )
- #define MultiU24X24toH16(intRes, longIn1, longIn2) \
- asm volatile ( \
- "clr r26 \n\t" \
- "mul %A1, %B2 \n\t" \
- "mov r27, r1 \n\t" \
- "mul %B1, %C2 \n\t" \
- "movw %A0, r0 \n\t" \
- "mul %C1, %C2 \n\t" \
- "add %B0, r0 \n\t" \
- "mul %C1, %B2 \n\t" \
- "add %A0, r0 \n\t" \
- "adc %B0, r1 \n\t" \
- "mul %A1, %C2 \n\t" \
- "add r27, r0 \n\t" \
- "adc %A0, r1 \n\t" \
- "adc %B0, r26 \n\t" \
- "mul %B1, %B2 \n\t" \
- "add r27, r0 \n\t" \
- "adc %A0, r1 \n\t" \
- "adc %B0, r26 \n\t" \
- "mul %C1, %A2 \n\t" \
- "add r27, r0 \n\t" \
- "adc %A0, r1 \n\t" \
- "adc %B0, r26 \n\t" \
- "mul %B1, %A2 \n\t" \
- "add r27, r1 \n\t" \
- "adc %A0, r26 \n\t" \
- "adc %B0, r26 \n\t" \
- "lsr r27 \n\t" \
- "adc %A0, r26 \n\t" \
- "adc %B0, r26 \n\t" \
- "clr r1 \n\t" \
- : \
- "=&r" (intRes) \
- : \
- "d" (longIn1), \
- "d" (longIn2) \
- : \
- "r26" , "r27" \
- )
- #else
- void MultiU16X8toH16(unsigned short& intRes, unsigned char& charIn1, unsigned short& intIn2)
- {
- }
- void MultiU24X24toH16(uint16_t& intRes, int32_t& longIn1, long& longIn2)
- {
- }
- #endif
- void checkHitEndstops()
- {
- if( endstop_x_hit || endstop_y_hit || endstop_z_hit) {
- SERIAL_ECHO_START;
- SERIAL_ECHORPGM(_T(MSG_ENDSTOPS_HIT));
- if(endstop_x_hit) {
- SERIAL_ECHOPAIR(" X:",(float)endstops_trigsteps[X_AXIS]/axis_steps_per_unit[X_AXIS]);
- LCD_MESSAGERPGM(CAT2(_T(MSG_ENDSTOPS_HIT), PSTR("X")));
- }
- if(endstop_y_hit) {
- SERIAL_ECHOPAIR(" Y:",(float)endstops_trigsteps[Y_AXIS]/axis_steps_per_unit[Y_AXIS]);
- LCD_MESSAGERPGM(CAT2(_T(MSG_ENDSTOPS_HIT), PSTR("Y")));
- }
- if(endstop_z_hit) {
- SERIAL_ECHOPAIR(" Z:",(float)endstops_trigsteps[Z_AXIS]/axis_steps_per_unit[Z_AXIS]);
- LCD_MESSAGERPGM(CAT2(_T(MSG_ENDSTOPS_HIT),PSTR("Z")));
- }
- SERIAL_ECHOLN("");
- endstop_x_hit=false;
- endstop_y_hit=false;
- endstop_z_hit=false;
- #if defined(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) && defined(SDSUPPORT)
- if (abort_on_endstop_hit)
- {
- card.sdprinting = false;
- card.closefile();
- quickStop();
- setTargetHotend0(0);
- setTargetHotend1(0);
- setTargetHotend2(0);
- }
- #endif
- }
- }
- bool endstops_hit_on_purpose()
- {
- bool hit = endstop_x_hit || endstop_y_hit || endstop_z_hit;
- endstop_x_hit=false;
- endstop_y_hit=false;
- endstop_z_hit=false;
- return hit;
- }
- bool endstop_z_hit_on_purpose()
- {
- bool hit = endstop_z_hit;
- endstop_z_hit=false;
- return hit;
- }
- bool enable_endstops(bool check)
- {
- bool old = check_endstops;
- check_endstops = check;
- return old;
- }
- bool enable_z_endstop(bool check)
- {
- bool old = check_z_endstop;
- check_z_endstop = check;
- endstop_z_hit = false;
- return old;
- }
- void invert_z_endstop(bool endstop_invert)
- {
- z_endstop_invert = endstop_invert;
- }
- FORCE_INLINE unsigned short calc_timer(uint16_t step_rate) {
- unsigned short timer;
- if(step_rate > MAX_STEP_FREQUENCY) step_rate = MAX_STEP_FREQUENCY;
- if(step_rate > 20000) {
- step_rate = (step_rate >> 2)&0x3fff;
- step_loops = 4;
- }
- else if(step_rate > 10000) {
- step_rate = (step_rate >> 1)&0x7fff;
- step_loops = 2;
- }
- else {
- step_loops = 1;
- }
- if(step_rate < (F_CPU/500000)) step_rate = (F_CPU/500000);
- step_rate -= (F_CPU/500000);
- if(step_rate >= (8*256)){
- unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate>>8)][0];
- unsigned char tmp_step_rate = (step_rate & 0x00ff);
- unsigned short gain = (unsigned short)pgm_read_word_near(table_address+2);
- MultiU16X8toH16(timer, tmp_step_rate, gain);
- timer = (unsigned short)pgm_read_word_near(table_address) - timer;
- }
- else {
- unsigned short table_address = (unsigned short)&speed_lookuptable_slow[0][0];
- table_address += ((step_rate)>>1) & 0xfffc;
- timer = (unsigned short)pgm_read_word_near(table_address);
- timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
- }
- if(timer < 100) { timer = 100; MYSERIAL.print(_i("Steprate too high: ")); MYSERIAL.println(step_rate); }
- return timer;
- }
- ISR(TIMER1_COMPA_vect) {
- #ifdef DEBUG_STACK_MONITOR
- uint16_t sp = SPL + 256 * SPH;
- if (sp < SP_min) SP_min = sp;
- #endif
- #ifdef LIN_ADVANCE
-
- bool run_main_isr = false;
- if (e_steps) {
-
- for (uint8_t i = estep_loops; e_steps && i --;) {
- WRITE_NC(E0_STEP_PIN, !INVERT_E_STEP_PIN);
- -- e_steps;
- WRITE_NC(E0_STEP_PIN, INVERT_E_STEP_PIN);
- }
- if (e_steps) {
-
- OCR1A = eISR_Rate;
- nextMainISR -= eISR_Rate;
- } else if (! (nextMainISR & 0x8000) || nextMainISR < 16) {
-
- OCR1A = nextMainISR;
- } else {
-
-
- run_main_isr = true;
-
- }
-
- } else
- run_main_isr = true;
- if (run_main_isr)
- #endif
- isr();
-
-
- if (OCR1A < TCNT1 + 16) {
- #ifdef DEBUG_STEPPER_TIMER_MISSED
-
-
-
-
- if (OCR1A + 40 < TCNT1) {
-
-
- stepper_timer_overflow_state = true;
- stepper_timer_overflow_last = TCNT1 - OCR1A;
-
- WRITE(BEEPER, HIGH);
- }
- #endif
-
- OCR1A = TCNT1 + 16;
- }
- }
- uint8_t last_dir_bits = 0;
- #ifdef BACKLASH_X
- uint8_t st_backlash_x = 0;
- #endif
- #ifdef BACKLASH_Y
- uint8_t st_backlash_y = 0;
- #endif
- FORCE_INLINE void stepper_next_block()
- {
-
-
- current_block = plan_get_current_block();
- if (current_block != NULL) {
- #ifdef BACKLASH_X
- if (current_block->steps_x.wide)
- {
- if ((current_block->direction_bits ^ last_dir_bits) & 1)
- {
- printf_P(PSTR("BL %d\n"), (current_block->direction_bits & 1)?st_backlash_x:-st_backlash_x);
- if (current_block->direction_bits & 1)
- WRITE_NC(X_DIR_PIN, INVERT_X_DIR);
- else
- WRITE_NC(X_DIR_PIN, !INVERT_X_DIR);
- _delay_us(100);
- for (uint8_t i = 0; i < st_backlash_x; i++)
- {
- WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN);
- _delay_us(100);
- WRITE_NC(X_STEP_PIN, INVERT_X_STEP_PIN);
- _delay_us(900);
- }
- }
- last_dir_bits &= ~1;
- last_dir_bits |= current_block->direction_bits & 1;
- }
- #endif
- #ifdef BACKLASH_Y
- if (current_block->steps_y.wide)
- {
- if ((current_block->direction_bits ^ last_dir_bits) & 2)
- {
- printf_P(PSTR("BL %d\n"), (current_block->direction_bits & 2)?st_backlash_y:-st_backlash_y);
- if (current_block->direction_bits & 2)
- WRITE_NC(Y_DIR_PIN, INVERT_Y_DIR);
- else
- WRITE_NC(Y_DIR_PIN, !INVERT_Y_DIR);
- _delay_us(100);
- for (uint8_t i = 0; i < st_backlash_y; i++)
- {
- WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
- _delay_us(100);
- WRITE_NC(Y_STEP_PIN, INVERT_Y_STEP_PIN);
- _delay_us(900);
- }
- }
- last_dir_bits &= ~2;
- last_dir_bits |= current_block->direction_bits & 2;
- }
- #endif
- #ifdef FILAMENT_SENSOR
- fsensor_counter = 0;
- fsensor_st_block_begin(current_block);
- #endif
-
-
-
-
- deceleration_time = 0;
-
-
-
- step_loops_nominal = 0;
- acc_step_rate = uint16_t(current_block->initial_rate);
- acceleration_time = calc_timer(acc_step_rate);
- #ifdef LIN_ADVANCE
- current_estep_rate = ((unsigned long)acc_step_rate * current_block->abs_adv_steps_multiplier8) >> 17;
- #endif
- if (current_block->flag & BLOCK_FLAG_DDA_LOWRES) {
- counter_x.lo = -(current_block->step_event_count.lo >> 1);
- counter_y.lo = counter_x.lo;
- counter_z.lo = counter_x.lo;
- counter_e.lo = counter_x.lo;
- } else {
- counter_x.wide = -(current_block->step_event_count.wide >> 1);
- counter_y.wide = counter_x.wide;
- counter_z.wide = counter_x.wide;
- counter_e.wide = counter_x.wide;
- }
- step_events_completed.wide = 0;
-
- out_bits = current_block->direction_bits;
-
- if((out_bits & (1<<X_AXIS))!=0){
- WRITE_NC(X_DIR_PIN, INVERT_X_DIR);
- count_direction[X_AXIS]=-1;
- } else {
- WRITE_NC(X_DIR_PIN, !INVERT_X_DIR);
- count_direction[X_AXIS]=1;
- }
- if((out_bits & (1<<Y_AXIS))!=0){
- WRITE_NC(Y_DIR_PIN, INVERT_Y_DIR);
- count_direction[Y_AXIS]=-1;
- } else {
- WRITE_NC(Y_DIR_PIN, !INVERT_Y_DIR);
- count_direction[Y_AXIS]=1;
- }
- if ((out_bits & (1<<Z_AXIS)) != 0) {
- WRITE_NC(Z_DIR_PIN,INVERT_Z_DIR);
- count_direction[Z_AXIS]=-1;
- } else {
- WRITE_NC(Z_DIR_PIN,!INVERT_Z_DIR);
- count_direction[Z_AXIS]=1;
- }
- if ((out_bits & (1 << E_AXIS)) != 0) {
- #ifndef LIN_ADVANCE
- WRITE(E0_DIR_PIN,
- #ifdef SNMM
- (mmu_extruder == 0 || mmu_extruder == 2) ? !INVERT_E0_DIR :
- #endif
- INVERT_E0_DIR);
- #endif
- count_direction[E_AXIS] = -1;
- } else {
- #ifndef LIN_ADVANCE
- WRITE(E0_DIR_PIN,
- #ifdef SNMM
- (mmu_extruder == 0 || mmu_extruder == 2) ? INVERT_E0_DIR :
- #endif
- !INVERT_E0_DIR);
- #endif
- count_direction[E_AXIS] = 1;
- }
- }
- else {
- OCR1A = 2000;
- }
-
- }
- FORCE_INLINE void stepper_check_endstops()
- {
- if(check_endstops)
- {
- #ifndef COREXY
- if ((out_bits & (1<<X_AXIS)) != 0)
- #else
- if ((((out_bits & (1<<X_AXIS)) != 0)&&(out_bits & (1<<Y_AXIS)) != 0))
- #endif
- {
- #if ( (defined(X_MIN_PIN) && (X_MIN_PIN > -1)) || defined(TMC2130_SG_HOMING) ) && !defined(DEBUG_DISABLE_XMINLIMIT)
- #ifdef TMC2130_SG_HOMING
-
- x_min_endstop = (READ(X_TMC2130_DIAG) != 0);
- #else
-
- x_min_endstop = (READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING);
- #endif
- if(x_min_endstop && old_x_min_endstop && (current_block->steps_x.wide > 0)) {
- endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
- endstop_x_hit=true;
- step_events_completed.wide = current_block->step_event_count.wide;
- }
- old_x_min_endstop = x_min_endstop;
- #endif
- } else {
- #if ( (defined(X_MAX_PIN) && (X_MAX_PIN > -1)) || defined(TMC2130_SG_HOMING) ) && !defined(DEBUG_DISABLE_XMAXLIMIT)
- #ifdef TMC2130_SG_HOMING
-
- x_max_endstop = (READ(X_TMC2130_DIAG) != 0);
- #else
-
- x_max_endstop = (READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING);
- #endif
- if(x_max_endstop && old_x_max_endstop && (current_block->steps_x.wide > 0)){
- endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
- endstop_x_hit=true;
- step_events_completed.wide = current_block->step_event_count.wide;
- }
- old_x_max_endstop = x_max_endstop;
- #endif
- }
- #ifndef COREXY
- if ((out_bits & (1<<Y_AXIS)) != 0)
- #else
- if ((((out_bits & (1<<X_AXIS)) != 0)&&(out_bits & (1<<Y_AXIS)) == 0))
- #endif
- {
- #if ( (defined(Y_MIN_PIN) && (Y_MIN_PIN > -1)) || defined(TMC2130_SG_HOMING) ) && !defined(DEBUG_DISABLE_YMINLIMIT)
- #ifdef TMC2130_SG_HOMING
-
- y_min_endstop = (READ(Y_TMC2130_DIAG) != 0);
- #else
-
- y_min_endstop = (READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING);
- #endif
- if(y_min_endstop && old_y_min_endstop && (current_block->steps_y.wide > 0)) {
- endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
- endstop_y_hit=true;
- step_events_completed.wide = current_block->step_event_count.wide;
- }
- old_y_min_endstop = y_min_endstop;
- #endif
- } else {
- #if ( (defined(Y_MAX_PIN) && (Y_MAX_PIN > -1)) || defined(TMC2130_SG_HOMING) ) && !defined(DEBUG_DISABLE_YMAXLIMIT)
- #ifdef TMC2130_SG_HOMING
-
- y_max_endstop = (READ(Y_TMC2130_DIAG) != 0);
- #else
-
- y_max_endstop = (READ(Y_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING);
- #endif
- if(y_max_endstop && old_y_max_endstop && (current_block->steps_y.wide > 0)){
- endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
- endstop_y_hit=true;
- step_events_completed.wide = current_block->step_event_count.wide;
- }
- old_y_max_endstop = y_max_endstop;
- #endif
- }
- if ((out_bits & (1<<Z_AXIS)) != 0)
- {
- #if defined(Z_MIN_PIN) && (Z_MIN_PIN > -1) && !defined(DEBUG_DISABLE_ZMINLIMIT)
- if (! check_z_endstop) {
- #ifdef TMC2130_SG_HOMING
-
- #ifdef TMC2130_STEALTH_Z
- if ((tmc2130_mode == TMC2130_MODE_SILENT) && !(tmc2130_sg_homing_axes_mask & 0x04))
- z_min_endstop = (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
- else
- #endif
- z_min_endstop = (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING) || (READ(Z_TMC2130_DIAG) != 0);
- #else
- z_min_endstop = (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
- #endif
- if(z_min_endstop && old_z_min_endstop && (current_block->steps_z.wide > 0)) {
- endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
- endstop_z_hit=true;
- step_events_completed.wide = current_block->step_event_count.wide;
- }
- old_z_min_endstop = z_min_endstop;
- }
- #endif
- } else {
- #if defined(Z_MAX_PIN) && (Z_MAX_PIN > -1) && !defined(DEBUG_DISABLE_ZMAXLIMIT)
- #ifdef TMC2130_SG_HOMING
-
- #ifdef TMC2130_STEALTH_Z
- if ((tmc2130_mode == TMC2130_MODE_SILENT) && !(tmc2130_sg_homing_axes_mask & 0x04))
- z_max_endstop = false;
- else
- #endif
- z_max_endstop = (READ(Z_TMC2130_DIAG) != 0);
- #else
- z_max_endstop = (READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING);
- #endif
- if(z_max_endstop && old_z_max_endstop && (current_block->steps_z.wide > 0)) {
- endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
- endstop_z_hit=true;
- step_events_completed.wide = current_block->step_event_count.wide;
- }
- old_z_max_endstop = z_max_endstop;
- #endif
- }
- }
-
- #if defined(Z_MIN_PIN) && (Z_MIN_PIN > -1) && !defined(DEBUG_DISABLE_ZMINLIMIT)
- if (check_z_endstop) {
-
-
- #ifdef TMC2130_SG_HOMING
-
- #ifdef TMC2130_STEALTH_Z
- if ((tmc2130_mode == TMC2130_MODE_SILENT) && !(tmc2130_sg_homing_axes_mask & 0x04))
- z_min_endstop = (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
- else
- #endif
- z_min_endstop = (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING) || (READ(Z_TMC2130_DIAG) != 0);
- #else
- z_min_endstop = (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
- #endif
- if(z_min_endstop && old_z_min_endstop) {
- endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
- endstop_z_hit=true;
- step_events_completed.wide = current_block->step_event_count.wide;
- }
- old_z_min_endstop = z_min_endstop;
- }
- #endif
- }
- FORCE_INLINE void stepper_tick_lowres()
- {
- for (uint8_t i=0; i < step_loops; ++ i) {
- MSerial.checkRx();
-
- counter_x.lo += current_block->steps_x.lo;
- if (counter_x.lo > 0) {
- WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN);
- #ifdef DEBUG_XSTEP_DUP_PIN
- WRITE_NC(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN);
- #endif
- counter_x.lo -= current_block->step_event_count.lo;
- count_position[X_AXIS]+=count_direction[X_AXIS];
- WRITE_NC(X_STEP_PIN, INVERT_X_STEP_PIN);
- #ifdef DEBUG_XSTEP_DUP_PIN
- WRITE_NC(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN);
- #endif
- }
-
- counter_y.lo += current_block->steps_y.lo;
- if (counter_y.lo > 0) {
- WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
- #ifdef DEBUG_YSTEP_DUP_PIN
- WRITE_NC(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN);
- #endif
- counter_y.lo -= current_block->step_event_count.lo;
- count_position[Y_AXIS]+=count_direction[Y_AXIS];
- WRITE_NC(Y_STEP_PIN, INVERT_Y_STEP_PIN);
- #ifdef DEBUG_YSTEP_DUP_PIN
- WRITE_NC(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN);
- #endif
- }
-
- counter_z.lo += current_block->steps_z.lo;
- if (counter_z.lo > 0) {
- WRITE_NC(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
- counter_z.lo -= current_block->step_event_count.lo;
- count_position[Z_AXIS]+=count_direction[Z_AXIS];
- WRITE_NC(Z_STEP_PIN, INVERT_Z_STEP_PIN);
- }
-
- counter_e.lo += current_block->steps_e.lo;
- if (counter_e.lo > 0) {
- #ifndef LIN_ADVANCE
- WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
- #endif
- counter_e.lo -= current_block->step_event_count.lo;
- count_position[E_AXIS] += count_direction[E_AXIS];
- #ifdef LIN_ADVANCE
- ++ e_steps;
- #else
- #ifdef FILAMENT_SENSOR
- ++ fsensor_counter;
- #endif
- WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN);
- #endif
- }
- if(++ step_events_completed.lo >= current_block->step_event_count.lo)
- break;
- }
- }
- FORCE_INLINE void stepper_tick_highres()
- {
- for (uint8_t i=0; i < step_loops; ++ i) {
- MSerial.checkRx();
-
- counter_x.wide += current_block->steps_x.wide;
- if (counter_x.wide > 0) {
- WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN);
- #ifdef DEBUG_XSTEP_DUP_PIN
- WRITE_NC(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN);
- #endif
- counter_x.wide -= current_block->step_event_count.wide;
- count_position[X_AXIS]+=count_direction[X_AXIS];
- WRITE_NC(X_STEP_PIN, INVERT_X_STEP_PIN);
- #ifdef DEBUG_XSTEP_DUP_PIN
- WRITE_NC(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN);
- #endif
- }
-
- counter_y.wide += current_block->steps_y.wide;
- if (counter_y.wide > 0) {
- WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
- #ifdef DEBUG_YSTEP_DUP_PIN
- WRITE_NC(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN);
- #endif
- counter_y.wide -= current_block->step_event_count.wide;
- count_position[Y_AXIS]+=count_direction[Y_AXIS];
- WRITE_NC(Y_STEP_PIN, INVERT_Y_STEP_PIN);
- #ifdef DEBUG_YSTEP_DUP_PIN
- WRITE_NC(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN);
- #endif
- }
-
- counter_z.wide += current_block->steps_z.wide;
- if (counter_z.wide > 0) {
- WRITE_NC(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
- counter_z.wide -= current_block->step_event_count.wide;
- count_position[Z_AXIS]+=count_direction[Z_AXIS];
- WRITE_NC(Z_STEP_PIN, INVERT_Z_STEP_PIN);
- }
-
- counter_e.wide += current_block->steps_e.wide;
- if (counter_e.wide > 0) {
- #ifndef LIN_ADVANCE
- WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
- #endif
- counter_e.wide -= current_block->step_event_count.wide;
- count_position[E_AXIS]+=count_direction[E_AXIS];
- #ifdef LIN_ADVANCE
- ++ e_steps;
- #else
- #ifdef FILAMENT_SENSOR
- ++ fsensor_counter;
- #endif
- WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN);
- #endif
- }
- if(++ step_events_completed.wide >= current_block->step_event_count.wide)
- break;
- }
- }
- #define LIN_ADV_FIRST_TICK_DELAY 100
- FORCE_INLINE void isr() {
-
-
-
- if (current_block == NULL)
- stepper_next_block();
- if (current_block != NULL)
- {
- stepper_check_endstops();
- #ifdef LIN_ADVANCE
- e_steps = 0;
- #endif
- if (current_block->flag & BLOCK_FLAG_DDA_LOWRES)
- stepper_tick_lowres();
- else
- stepper_tick_highres();
- #ifdef LIN_ADVANCE
- if (out_bits&(1<<E_AXIS))
-
- e_steps = - e_steps;
- if (current_block->use_advance_lead) {
-
-
-
- e_steps += current_estep_rate - current_adv_steps;
- #if 0
- if (abs(esteps_inc) > 4) {
- LOGIC_ANALYZER_SERIAL_TX_WRITE(esteps_inc);
- if (esteps_inc < -511 || esteps_inc > 511)
- LOGIC_ANALYZER_SERIAL_TX_WRITE(esteps_inc >> 9);
- }
- #endif
- current_adv_steps = current_estep_rate;
- }
-
- if (e_steps) {
-
-
- {
- bool neg = e_steps < 0;
- bool dir =
- #ifdef SNMM
- (neg == (mmu_extruder & 1))
- #else
- neg
- #endif
- ? INVERT_E0_DIR : !INVERT_E0_DIR;
- WRITE_NC(E0_DIR_PIN, dir);
- if (neg)
-
- e_steps = - e_steps;
- }
-
- estep_loops = (e_steps & 0x0ff00) ? 4 : e_steps;
- if (step_loops < estep_loops)
- estep_loops = step_loops;
- #ifdef FILAMENT_SENSOR
- fsensor_counter += estep_loops;
- #endif
- do {
- WRITE_NC(E0_STEP_PIN, !INVERT_E_STEP_PIN);
- -- e_steps;
- WRITE_NC(E0_STEP_PIN, INVERT_E_STEP_PIN);
- } while (-- estep_loops != 0);
-
- MSerial.checkRx();
- }
- #endif
-
-
-
- {
-
- if (step_events_completed.wide <= (unsigned long int)current_block->accelerate_until) {
-
- MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
- acc_step_rate += uint16_t(current_block->initial_rate);
-
- if(acc_step_rate > uint16_t(current_block->nominal_rate))
- acc_step_rate = current_block->nominal_rate;
-
- uint16_t timer = calc_timer(acc_step_rate);
- _NEXT_ISR(timer);
- acceleration_time += timer;
- #ifdef LIN_ADVANCE
- if (current_block->use_advance_lead)
-
- current_estep_rate = ((uint32_t)acc_step_rate * current_block->abs_adv_steps_multiplier8) >> 17;
- #endif
- }
- else if (step_events_completed.wide > (unsigned long int)current_block->decelerate_after) {
- uint16_t step_rate;
- MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate);
- step_rate = acc_step_rate - step_rate;
- if ((step_rate & 0x8000) || step_rate < uint16_t(current_block->final_rate)) {
-
- step_rate = uint16_t(current_block->final_rate);
- }
-
- uint16_t timer = calc_timer(step_rate);
- _NEXT_ISR(timer);
- deceleration_time += timer;
- #ifdef LIN_ADVANCE
- if (current_block->use_advance_lead)
- current_estep_rate = ((uint32_t)step_rate * current_block->abs_adv_steps_multiplier8) >> 17;
- #endif
- }
- else {
- if (! step_loops_nominal) {
-
-
- OCR1A_nominal = calc_timer(uint16_t(current_block->nominal_rate));
- step_loops_nominal = step_loops;
- #ifdef LIN_ADVANCE
- if (current_block->use_advance_lead)
- current_estep_rate = (current_block->nominal_rate * current_block->abs_adv_steps_multiplier8) >> 17;
- #endif
- }
- _NEXT_ISR(OCR1A_nominal);
- }
-
- }
- #ifdef LIN_ADVANCE
- if (e_steps && current_block->use_advance_lead) {
-
- MSerial.checkRx();
-
- uint16_t now = TCNT1;
-
- uint16_t to_go = nextMainISR - now - LIN_ADV_FIRST_TICK_DELAY;
- eISR_Rate = 0;
- if ((to_go & 0x8000) == 0) {
-
-
- uint8_t ticks = to_go >> 8;
- if (ticks == 1) {
-
- estep_loops = 255;
- eISR_Rate = 1;
- } else if ((e_steps & 0x0ff00) == 0) {
-
- if (uint8_t(e_steps) <= ticks) {
-
- eISR_Rate = to_go / uint8_t(e_steps);
- estep_loops = 1;
- } else if (ticks != 0) {
-
- uint8_t e = uint8_t(e_steps) >> 1;
- estep_loops = 2;
- while (e > ticks) {
- e >>= 1;
- estep_loops <<= 1;
- }
-
-
-
- eISR_Rate = to_go / ticks;
- }
- } else {
-
-
- estep_loops = 2;
- uint16_t e = e_steps >> 1;
- while (e & 0x0ff00) {
- e >>= 1;
- estep_loops <<= 1;
- }
- while (uint8_t(e) > ticks) {
- e >>= 1;
- estep_loops <<= 1;
- }
-
-
-
- eISR_Rate = to_go / ticks;
- }
- }
- if (eISR_Rate == 0) {
-
-
- #ifdef FILAMENT_SENSOR
- fsensor_counter += e_steps;
- #endif
- MSerial.checkRx();
- do {
- WRITE_NC(E0_STEP_PIN, !INVERT_E_STEP_PIN);
- -- e_steps;
- WRITE_NC(E0_STEP_PIN, INVERT_E_STEP_PIN);
- } while (e_steps);
- OCR1A = nextMainISR;
- } else {
-
- nextMainISR -= LIN_ADV_FIRST_TICK_DELAY;
- OCR1A = now + LIN_ADV_FIRST_TICK_DELAY;
- }
-
- } else
- OCR1A = nextMainISR;
- #endif
-
- if (step_events_completed.wide >= current_block->step_event_count.wide) {
- #ifdef FILAMENT_SENSOR
- fsensor_st_block_chunk(current_block, fsensor_counter);
- fsensor_counter = 0;
- #endif
- current_block = NULL;
- plan_discard_current_block();
- }
- #ifdef FILAMENT_SENSOR
- else if (fsensor_counter >= fsensor_chunk_len)
- {
- fsensor_st_block_chunk(current_block, fsensor_counter);
- fsensor_counter = 0;
- }
- #endif
- }
- #ifdef TMC2130
- tmc2130_st_isr();
- #endif
-
- }
- #ifdef LIN_ADVANCE
- void clear_current_adv_vars() {
- e_steps = 0;
- current_adv_steps = 0;
- }
- #endif
-
- void st_init()
- {
- #ifdef TMC2130
- tmc2130_init();
- #endif
- st_current_init();
- microstep_init();
-
- #if defined(X_DIR_PIN) && X_DIR_PIN > -1
- SET_OUTPUT(X_DIR_PIN);
- #endif
- #if defined(X2_DIR_PIN) && X2_DIR_PIN > -1
- SET_OUTPUT(X2_DIR_PIN);
- #endif
- #if defined(Y_DIR_PIN) && Y_DIR_PIN > -1
- SET_OUTPUT(Y_DIR_PIN);
-
- #if defined(Y_DUAL_STEPPER_DRIVERS) && defined(Y2_DIR_PIN) && (Y2_DIR_PIN > -1)
- SET_OUTPUT(Y2_DIR_PIN);
- #endif
- #endif
- #if defined(Z_DIR_PIN) && Z_DIR_PIN > -1
- SET_OUTPUT(Z_DIR_PIN);
- #if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_DIR_PIN) && (Z2_DIR_PIN > -1)
- SET_OUTPUT(Z2_DIR_PIN);
- #endif
- #endif
- #if defined(E0_DIR_PIN) && E0_DIR_PIN > -1
- SET_OUTPUT(E0_DIR_PIN);
- #endif
- #if defined(E1_DIR_PIN) && (E1_DIR_PIN > -1)
- SET_OUTPUT(E1_DIR_PIN);
- #endif
- #if defined(E2_DIR_PIN) && (E2_DIR_PIN > -1)
- SET_OUTPUT(E2_DIR_PIN);
- #endif
-
- #if defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1
- SET_OUTPUT(X_ENABLE_PIN);
- if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
- #endif
- #if defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1
- SET_OUTPUT(X2_ENABLE_PIN);
- if(!X_ENABLE_ON) WRITE(X2_ENABLE_PIN,HIGH);
- #endif
- #if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1
- SET_OUTPUT(Y_ENABLE_PIN);
- if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
-
- #if defined(Y_DUAL_STEPPER_DRIVERS) && defined(Y2_ENABLE_PIN) && (Y2_ENABLE_PIN > -1)
- SET_OUTPUT(Y2_ENABLE_PIN);
- if(!Y_ENABLE_ON) WRITE(Y2_ENABLE_PIN,HIGH);
- #endif
- #endif
- #if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
- SET_OUTPUT(Z_ENABLE_PIN);
- if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
- #if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_ENABLE_PIN) && (Z2_ENABLE_PIN > -1)
- SET_OUTPUT(Z2_ENABLE_PIN);
- if(!Z_ENABLE_ON) WRITE(Z2_ENABLE_PIN,HIGH);
- #endif
- #endif
- #if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1)
- SET_OUTPUT(E0_ENABLE_PIN);
- if(!E_ENABLE_ON) WRITE(E0_ENABLE_PIN,HIGH);
- #endif
- #if defined(E1_ENABLE_PIN) && (E1_ENABLE_PIN > -1)
- SET_OUTPUT(E1_ENABLE_PIN);
- if(!E_ENABLE_ON) WRITE(E1_ENABLE_PIN,HIGH);
- #endif
- #if defined(E2_ENABLE_PIN) && (E2_ENABLE_PIN > -1)
- SET_OUTPUT(E2_ENABLE_PIN);
- if(!E_ENABLE_ON) WRITE(E2_ENABLE_PIN,HIGH);
- #endif
-
- #ifdef TMC2130_SG_HOMING
- SET_INPUT(X_TMC2130_DIAG);
- WRITE(X_TMC2130_DIAG,HIGH);
-
- SET_INPUT(Y_TMC2130_DIAG);
- WRITE(Y_TMC2130_DIAG,HIGH);
-
- SET_INPUT(Z_TMC2130_DIAG);
- WRITE(Z_TMC2130_DIAG,HIGH);
- SET_INPUT(E0_TMC2130_DIAG);
- WRITE(E0_TMC2130_DIAG,HIGH);
-
- #endif
-
- #if defined(X_MIN_PIN) && X_MIN_PIN > -1
- SET_INPUT(X_MIN_PIN);
- #ifdef ENDSTOPPULLUP_XMIN
- WRITE(X_MIN_PIN,HIGH);
- #endif
- #endif
- #if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
- SET_INPUT(Y_MIN_PIN);
- #ifdef ENDSTOPPULLUP_YMIN
- WRITE(Y_MIN_PIN,HIGH);
- #endif
- #endif
- #if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
- SET_INPUT(Z_MIN_PIN);
- #ifdef ENDSTOPPULLUP_ZMIN
- WRITE(Z_MIN_PIN,HIGH);
- #endif
- #endif
- #if defined(X_MAX_PIN) && X_MAX_PIN > -1
- SET_INPUT(X_MAX_PIN);
- #ifdef ENDSTOPPULLUP_XMAX
- WRITE(X_MAX_PIN,HIGH);
- #endif
- #endif
- #if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
- SET_INPUT(Y_MAX_PIN);
- #ifdef ENDSTOPPULLUP_YMAX
- WRITE(Y_MAX_PIN,HIGH);
- #endif
- #endif
- #if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
- SET_INPUT(Z_MAX_PIN);
- #ifdef ENDSTOPPULLUP_ZMAX
- WRITE(Z_MAX_PIN,HIGH);
- #endif
- #endif
- #if (defined(FANCHECK) && defined(TACH_0) && (TACH_0 > -1))
- SET_INPUT(TACH_0);
- #ifdef TACH0PULLUP
- WRITE(TACH_0, HIGH);
- #endif
- #endif
-
- #if defined(X_STEP_PIN) && (X_STEP_PIN > -1)
- SET_OUTPUT(X_STEP_PIN);
- WRITE(X_STEP_PIN,INVERT_X_STEP_PIN);
- #ifdef DEBUG_XSTEP_DUP_PIN
- SET_OUTPUT(DEBUG_XSTEP_DUP_PIN);
- WRITE(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN);
- #endif
- disable_x();
- #endif
- #if defined(X2_STEP_PIN) && (X2_STEP_PIN > -1)
- SET_OUTPUT(X2_STEP_PIN);
- WRITE(X2_STEP_PIN,INVERT_X_STEP_PIN);
- disable_x();
- #endif
- #if defined(Y_STEP_PIN) && (Y_STEP_PIN > -1)
- SET_OUTPUT(Y_STEP_PIN);
- WRITE(Y_STEP_PIN,INVERT_Y_STEP_PIN);
- #ifdef DEBUG_YSTEP_DUP_PIN
- SET_OUTPUT(DEBUG_YSTEP_DUP_PIN);
- WRITE(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN);
- #endif
- #if defined(Y_DUAL_STEPPER_DRIVERS) && defined(Y2_STEP_PIN) && (Y2_STEP_PIN > -1)
- SET_OUTPUT(Y2_STEP_PIN);
- WRITE(Y2_STEP_PIN,INVERT_Y_STEP_PIN);
- #endif
- disable_y();
- #endif
- #if defined(Z_STEP_PIN) && (Z_STEP_PIN > -1)
- SET_OUTPUT(Z_STEP_PIN);
- WRITE(Z_STEP_PIN,INVERT_Z_STEP_PIN);
- #if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_STEP_PIN) && (Z2_STEP_PIN > -1)
- SET_OUTPUT(Z2_STEP_PIN);
- WRITE(Z2_STEP_PIN,INVERT_Z_STEP_PIN);
- #endif
- disable_z();
- #endif
- #if defined(E0_STEP_PIN) && (E0_STEP_PIN > -1)
- SET_OUTPUT(E0_STEP_PIN);
- WRITE(E0_STEP_PIN,INVERT_E_STEP_PIN);
- disable_e0();
- #endif
- #if defined(E1_STEP_PIN) && (E1_STEP_PIN > -1)
- SET_OUTPUT(E1_STEP_PIN);
- WRITE(E1_STEP_PIN,INVERT_E_STEP_PIN);
- disable_e1();
- #endif
- #if defined(E2_STEP_PIN) && (E2_STEP_PIN > -1)
- SET_OUTPUT(E2_STEP_PIN);
- WRITE(E2_STEP_PIN,INVERT_E_STEP_PIN);
- disable_e2();
- #endif
-
- TCCR1B &= ~(1<<WGM13);
- TCCR1B |= (1<<WGM12);
- TCCR1A &= ~(1<<WGM11);
- TCCR1A &= ~(1<<WGM10);
-
- TCCR1A &= ~(3<<COM1A0);
- TCCR1A &= ~(3<<COM1B0);
-
-
-
-
-
- TCCR1B = (TCCR1B & ~(0x07<<CS10)) | (2<<CS10);
-
- OCR1A = 0x4000;
- TCNT1 = 0;
- ENABLE_STEPPER_DRIVER_INTERRUPT();
- #ifdef LIN_ADVANCE
- e_steps = 0;
- current_adv_steps = 0;
- #endif
-
- enable_endstops(true);
- sei();
- }
- void st_synchronize()
- {
- while(blocks_queued())
- {
- #ifdef TMC2130
- manage_heater();
-
- if (!tmc2130_update_sg())
- {
- manage_inactivity(true);
- lcd_update(0);
- }
- #else
- manage_heater();
-
- manage_inactivity(true);
- lcd_update(0);
- #endif
- }
- }
- void st_set_position(const long &x, const long &y, const long &z, const long &e)
- {
- CRITICAL_SECTION_START;
-
-
-
-
-
- count_position[X_AXIS] = x;
- count_position[Y_AXIS] = y;
- count_position[Z_AXIS] = z;
- count_position[E_AXIS] = e;
- CRITICAL_SECTION_END;
- }
- void st_set_e_position(const long &e)
- {
- CRITICAL_SECTION_START;
- count_position[E_AXIS] = e;
- CRITICAL_SECTION_END;
- }
- long st_get_position(uint8_t axis)
- {
- long count_pos;
- CRITICAL_SECTION_START;
- count_pos = count_position[axis];
- CRITICAL_SECTION_END;
- return count_pos;
- }
- void st_get_position_xy(long &x, long &y)
- {
- CRITICAL_SECTION_START;
- x = count_position[X_AXIS];
- y = count_position[Y_AXIS];
- CRITICAL_SECTION_END;
- }
- float st_get_position_mm(uint8_t axis)
- {
- float steper_position_in_steps = st_get_position(axis);
- return steper_position_in_steps / axis_steps_per_unit[axis];
- }
- void finishAndDisableSteppers()
- {
- st_synchronize();
- disable_x();
- disable_y();
- disable_z();
- disable_e0();
- disable_e1();
- disable_e2();
- }
- void quickStop()
- {
- DISABLE_STEPPER_DRIVER_INTERRUPT();
- while (blocks_queued()) plan_discard_current_block();
- current_block = NULL;
- st_reset_timer();
- ENABLE_STEPPER_DRIVER_INTERRUPT();
- }
- #ifdef BABYSTEPPING
- void babystep(const uint8_t axis,const bool direction)
- {
-
-
- switch(axis)
- {
- case X_AXIS:
- {
- enable_x();
- uint8_t old_x_dir_pin= READ(X_DIR_PIN);
-
-
- WRITE(X_DIR_PIN,(INVERT_X_DIR)^direction);
-
-
- WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
- #ifdef DEBUG_XSTEP_DUP_PIN
- WRITE(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN);
- #endif
- delayMicroseconds(1);
- WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
- #ifdef DEBUG_XSTEP_DUP_PIN
- WRITE(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN);
- #endif
-
- WRITE(X_DIR_PIN,old_x_dir_pin);
- }
- break;
- case Y_AXIS:
- {
- enable_y();
- uint8_t old_y_dir_pin= READ(Y_DIR_PIN);
-
-
- WRITE(Y_DIR_PIN,(INVERT_Y_DIR)^direction);
-
-
- WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
- #ifdef DEBUG_YSTEP_DUP_PIN
- WRITE(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN);
- #endif
- delayMicroseconds(1);
- WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
- #ifdef DEBUG_YSTEP_DUP_PIN
- WRITE(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN);
- #endif
-
- WRITE(Y_DIR_PIN,old_y_dir_pin);
- }
- break;
-
- case Z_AXIS:
- {
- enable_z();
- uint8_t old_z_dir_pin= READ(Z_DIR_PIN);
-
- WRITE(Z_DIR_PIN,(INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z);
- #ifdef Z_DUAL_STEPPER_DRIVERS
- WRITE(Z2_DIR_PIN,(INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z);
- #endif
-
- WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
- #ifdef Z_DUAL_STEPPER_DRIVERS
- WRITE(Z2_STEP_PIN, !INVERT_Z_STEP_PIN);
- #endif
- delayMicroseconds(1);
- WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN);
- #ifdef Z_DUAL_STEPPER_DRIVERS
- WRITE(Z2_STEP_PIN, INVERT_Z_STEP_PIN);
- #endif
-
- WRITE(Z_DIR_PIN,old_z_dir_pin);
- #ifdef Z_DUAL_STEPPER_DRIVERS
- WRITE(Z2_DIR_PIN,old_z_dir_pin);
- #endif
- }
- break;
-
- default: break;
- }
- }
- #endif
- #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
- void digitalPotWrite(int address, int value)
- {
- digitalWrite(DIGIPOTSS_PIN,LOW);
- SPI.transfer(address);
- SPI.transfer(value);
- digitalWrite(DIGIPOTSS_PIN,HIGH);
-
- }
- #endif
- void EEPROM_read_st(int pos, uint8_t* value, uint8_t size)
- {
- do
- {
- *value = eeprom_read_byte((unsigned char*)pos);
- pos++;
- value++;
- }while(--size);
- }
- void st_current_init()
- {
- uint8_t SilentMode = eeprom_read_byte((uint8_t*)EEPROM_SILENT);
- SilentModeMenu = SilentMode;
- #ifdef MOTOR_CURRENT_PWM_XY_PIN
- pinMode(MOTOR_CURRENT_PWM_XY_PIN, OUTPUT);
- pinMode(MOTOR_CURRENT_PWM_Z_PIN, OUTPUT);
- pinMode(MOTOR_CURRENT_PWM_E_PIN, OUTPUT);
- if((SilentMode == SILENT_MODE_OFF) || (farm_mode) ){
- motor_current_setting[0] = motor_current_setting_loud[0];
- motor_current_setting[1] = motor_current_setting_loud[1];
- motor_current_setting[2] = motor_current_setting_loud[2];
- }else{
- motor_current_setting[0] = motor_current_setting_silent[0];
- motor_current_setting[1] = motor_current_setting_silent[1];
- motor_current_setting[2] = motor_current_setting_silent[2];
- }
- st_current_set(0, motor_current_setting[0]);
- st_current_set(1, motor_current_setting[1]);
- st_current_set(2, motor_current_setting[2]);
-
- TCCR5B = (TCCR5B & ~(_BV(CS50) | _BV(CS51) | _BV(CS52))) | _BV(CS50);
- #endif
- }
- #ifdef MOTOR_CURRENT_PWM_XY_PIN
- void st_current_set(uint8_t driver, int current)
- {
- if (driver == 0) analogWrite(MOTOR_CURRENT_PWM_XY_PIN, (long)current * 255L / (long)MOTOR_CURRENT_PWM_RANGE);
- if (driver == 1) analogWrite(MOTOR_CURRENT_PWM_Z_PIN, (long)current * 255L / (long)MOTOR_CURRENT_PWM_RANGE);
- if (driver == 2) analogWrite(MOTOR_CURRENT_PWM_E_PIN, (long)current * 255L / (long)MOTOR_CURRENT_PWM_RANGE);
- }
- #else
- void st_current_set(uint8_t, int ){}
- #endif
- void microstep_init()
- {
- #if defined(E1_MS1_PIN) && E1_MS1_PIN > -1
- pinMode(E1_MS1_PIN,OUTPUT);
- pinMode(E1_MS2_PIN,OUTPUT);
- #endif
- #if defined(X_MS1_PIN) && X_MS1_PIN > -1
- const uint8_t microstep_modes[] = MICROSTEP_MODES;
- pinMode(X_MS1_PIN,OUTPUT);
- pinMode(X_MS2_PIN,OUTPUT);
- pinMode(Y_MS1_PIN,OUTPUT);
- pinMode(Y_MS2_PIN,OUTPUT);
- pinMode(Z_MS1_PIN,OUTPUT);
- pinMode(Z_MS2_PIN,OUTPUT);
- pinMode(E0_MS1_PIN,OUTPUT);
- pinMode(E0_MS2_PIN,OUTPUT);
- for(int i=0;i<=4;i++) microstep_mode(i,microstep_modes[i]);
- #endif
- }
- #ifndef TMC2130
- void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2)
- {
- if(ms1 > -1) switch(driver)
- {
- case 0: digitalWrite( X_MS1_PIN,ms1); break;
- case 1: digitalWrite( Y_MS1_PIN,ms1); break;
- case 2: digitalWrite( Z_MS1_PIN,ms1); break;
- case 3: digitalWrite(E0_MS1_PIN,ms1); break;
- #if defined(E1_MS1_PIN) && E1_MS1_PIN > -1
- case 4: digitalWrite(E1_MS1_PIN,ms1); break;
- #endif
- }
- if(ms2 > -1) switch(driver)
- {
- case 0: digitalWrite( X_MS2_PIN,ms2); break;
- case 1: digitalWrite( Y_MS2_PIN,ms2); break;
- case 2: digitalWrite( Z_MS2_PIN,ms2); break;
- case 3: digitalWrite(E0_MS2_PIN,ms2); break;
- #if defined(E1_MS2_PIN) && E1_MS2_PIN > -1
- case 4: digitalWrite(E1_MS2_PIN,ms2); break;
- #endif
- }
- }
- void microstep_mode(uint8_t driver, uint8_t stepping_mode)
- {
- switch(stepping_mode)
- {
- case 1: microstep_ms(driver,MICROSTEP1); break;
- case 2: microstep_ms(driver,MICROSTEP2); break;
- case 4: microstep_ms(driver,MICROSTEP4); break;
- case 8: microstep_ms(driver,MICROSTEP8); break;
- case 16: microstep_ms(driver,MICROSTEP16); break;
- }
- }
- void microstep_readings()
- {
- SERIAL_PROTOCOLPGM("MS1,MS2 Pins\n");
- SERIAL_PROTOCOLPGM("X: ");
- SERIAL_PROTOCOL( digitalRead(X_MS1_PIN));
- SERIAL_PROTOCOLLN( digitalRead(X_MS2_PIN));
- SERIAL_PROTOCOLPGM("Y: ");
- SERIAL_PROTOCOL( digitalRead(Y_MS1_PIN));
- SERIAL_PROTOCOLLN( digitalRead(Y_MS2_PIN));
- SERIAL_PROTOCOLPGM("Z: ");
- SERIAL_PROTOCOL( digitalRead(Z_MS1_PIN));
- SERIAL_PROTOCOLLN( digitalRead(Z_MS2_PIN));
- SERIAL_PROTOCOLPGM("E0: ");
- SERIAL_PROTOCOL( digitalRead(E0_MS1_PIN));
- SERIAL_PROTOCOLLN( digitalRead(E0_MS2_PIN));
- #if defined(E1_MS1_PIN) && E1_MS1_PIN > -1
- SERIAL_PROTOCOLPGM("E1: ");
- SERIAL_PROTOCOL( digitalRead(E1_MS1_PIN));
- SERIAL_PROTOCOLLN( digitalRead(E1_MS2_PIN));
- #endif
- }
- #endif
|