1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258 |
- #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
- block_t *current_block;
- static unsigned char out_bits;
- static long counter_x,
- counter_y,
- counter_z,
- counter_e;
- volatile static unsigned long step_events_completed;
- #ifdef ADVANCE
- static long advance_rate, advance, final_advance = 0;
- static long old_advance = 0;
- static long e_steps[3];
- #endif
- static long acceleration_time, deceleration_time;
- static unsigned short acc_step_rate;
- static char step_loops;
- static unsigned short OCR1A_nominal;
- static unsigned short 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;
- int8_t SilentMode;
- volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0};
- volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1};
- #define CHECK_ENDSTOPS if(check_endstops)
- #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" \
- )
- #define ENABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 |= (1<<OCIE1A)
- #define DISABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 &= ~(1<<OCIE1A)
- void checkHitEndstops()
- {
- if( endstop_x_hit || endstop_y_hit || endstop_z_hit) {
- SERIAL_ECHO_START;
- SERIAL_ECHORPGM(MSG_ENDSTOPS_HIT);
- if(endstop_x_hit) {
- SERIAL_ECHOPAIR(" X:",(float)endstops_trigsteps[X_AXIS]/axis_steps_per_unit[X_AXIS]);
- LCD_MESSAGERPGM(CAT2(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(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(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;
- }
- // __________________________
- // /| |\ _________________ ^
- // / | | \ /| |\ |
- // / | | \ / | | \ s
- // / | | | | | \ p
- // / | | | | | \ e
- // +-----+------------------------+---+--+---------------+----+ e
- // | BLOCK 1 | BLOCK 2 | d
- //
- // time ----->
- void st_wake_up() {
-
- ENABLE_STEPPER_DRIVER_INTERRUPT();
- }
- void step_wait(){
- for(int8_t i=0; i < 6; i++){
- }
- }
- FORCE_INLINE unsigned short calc_timer(unsigned short 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(MSG_STEPPER_TOO_HIGH); MYSERIAL.println(step_rate); }
- return timer;
- }
- FORCE_INLINE void trapezoid_generator_reset() {
- #ifdef ADVANCE
- advance = current_block->initial_advance;
- final_advance = current_block->final_advance;
-
- e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
- old_advance = advance >>8;
- #endif
- deceleration_time = 0;
-
- OCR1A_nominal = calc_timer(current_block->nominal_rate);
-
- step_loops_nominal = step_loops;
- acc_step_rate = current_block->initial_rate;
- acceleration_time = calc_timer(acc_step_rate);
- OCR1A = acceleration_time;
- }
- ISR(TIMER1_COMPA_vect)
- {
-
- if (current_block == NULL) {
-
- current_block = plan_get_current_block();
- if (current_block != NULL) {
-
-
- trapezoid_generator_reset();
- counter_x = -(current_block->step_event_count >> 1);
- counter_y = counter_x;
- counter_z = counter_x;
- counter_e = counter_x;
- step_events_completed = 0;
- #ifdef Z_LATE_ENABLE
- if(current_block->steps_z > 0) {
- enable_z();
- OCR1A = 2000;
- return;
- }
- #endif
- }
- else {
- OCR1A=2000;
- }
- }
- if (current_block != NULL) {
-
- out_bits = current_block->direction_bits;
-
- if((out_bits & (1<<X_AXIS))!=0){
- WRITE(X_DIR_PIN, INVERT_X_DIR);
- count_direction[X_AXIS]=-1;
- }
- else{
- WRITE(X_DIR_PIN, !INVERT_X_DIR);
- count_direction[X_AXIS]=1;
- }
- if((out_bits & (1<<Y_AXIS))!=0){
- WRITE(Y_DIR_PIN, INVERT_Y_DIR);
-
- #ifdef Y_DUAL_STEPPER_DRIVERS
- WRITE(Y2_DIR_PIN, !(INVERT_Y_DIR == INVERT_Y2_VS_Y_DIR));
- #endif
-
- count_direction[Y_AXIS]=-1;
- }
- else{
- WRITE(Y_DIR_PIN, !INVERT_Y_DIR);
-
- #ifdef Y_DUAL_STEPPER_DRIVERS
- WRITE(Y2_DIR_PIN, (INVERT_Y_DIR == INVERT_Y2_VS_Y_DIR));
- #endif
-
- count_direction[Y_AXIS]=1;
- }
-
- #ifndef COREXY
- if ((out_bits & (1<<X_AXIS)) != 0) {
- #else
- if ((((out_bits & (1<<X_AXIS)) != 0)&&(out_bits & (1<<Y_AXIS)) != 0)) {
- #endif
- CHECK_ENDSTOPS
- {
- {
- #if defined(X_MIN_PIN) && X_MIN_PIN > -1
- bool x_min_endstop=(READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING);
- if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
- endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
- endstop_x_hit=true;
- step_events_completed = current_block->step_event_count;
- }
- old_x_min_endstop = x_min_endstop;
- #endif
- }
- }
- }
- else {
- CHECK_ENDSTOPS
- {
- {
- #if defined(X_MAX_PIN) && X_MAX_PIN > -1
- bool x_max_endstop=(READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING);
- if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
- endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
- endstop_x_hit=true;
- step_events_completed = current_block->step_event_count;
- }
- 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
- CHECK_ENDSTOPS
- {
- #if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
- bool y_min_endstop=(READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING);
- if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
- endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
- endstop_y_hit=true;
- step_events_completed = current_block->step_event_count;
- }
- old_y_min_endstop = y_min_endstop;
- #endif
- }
- }
- else {
- CHECK_ENDSTOPS
- {
- #if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
- bool y_max_endstop=(READ(Y_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING);
- if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
- endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
- endstop_y_hit=true;
- step_events_completed = current_block->step_event_count;
- }
- old_y_max_endstop = y_max_endstop;
- #endif
- }
- }
- if ((out_bits & (1<<Z_AXIS)) != 0) {
- WRITE(Z_DIR_PIN,INVERT_Z_DIR);
-
- #ifdef Z_DUAL_STEPPER_DRIVERS
- WRITE(Z2_DIR_PIN,INVERT_Z_DIR);
- #endif
- count_direction[Z_AXIS]=-1;
- if(check_endstops && ! check_z_endstop)
- {
- #if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
- bool z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
- if(z_min_endstop && old_z_min_endstop && (current_block->steps_z > 0)) {
- endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
- endstop_z_hit=true;
- step_events_completed = current_block->step_event_count;
- }
- old_z_min_endstop = z_min_endstop;
- #endif
- }
- }
- else {
- WRITE(Z_DIR_PIN,!INVERT_Z_DIR);
- #ifdef Z_DUAL_STEPPER_DRIVERS
- WRITE(Z2_DIR_PIN,!INVERT_Z_DIR);
- #endif
- count_direction[Z_AXIS]=1;
- CHECK_ENDSTOPS
- {
- #if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
- bool z_max_endstop=(READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING);
- if(z_max_endstop && old_z_max_endstop && (current_block->steps_z > 0)) {
- endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
- endstop_z_hit=true;
- step_events_completed = current_block->step_event_count;
- }
- old_z_max_endstop = z_max_endstop;
- #endif
- }
- }
-
- #if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
- if(check_z_endstop) {
-
-
- bool z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
- if(z_min_endstop && old_z_min_endstop) {
- endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
- endstop_z_hit=true;
- step_events_completed = current_block->step_event_count;
- }
- old_z_min_endstop = z_min_endstop;
- }
- #endif
- #ifndef ADVANCE
- if ((out_bits & (1<<E_AXIS)) != 0) {
- REV_E_DIR();
- count_direction[E_AXIS]=-1;
- }
- else {
- NORM_E_DIR();
- count_direction[E_AXIS]=1;
- }
- #endif
- for(int8_t i=0; i < step_loops; i++) {
- #ifndef AT90USB
- MSerial.checkRx();
- #endif
- #ifdef ADVANCE
- counter_e += current_block->steps_e;
- if (counter_e > 0) {
- counter_e -= current_block->step_event_count;
- if ((out_bits & (1<<E_AXIS)) != 0) {
- e_steps[current_block->active_extruder]--;
- }
- else {
- e_steps[current_block->active_extruder]++;
- }
- }
- #endif
- counter_x += current_block->steps_x;
- if (counter_x > 0) {
- WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
- counter_x -= current_block->step_event_count;
- count_position[X_AXIS]+=count_direction[X_AXIS];
- WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
- }
- counter_y += current_block->steps_y;
- if (counter_y > 0) {
- WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
-
- #ifdef Y_DUAL_STEPPER_DRIVERS
- WRITE(Y2_STEP_PIN, !INVERT_Y_STEP_PIN);
- #endif
-
- counter_y -= current_block->step_event_count;
- count_position[Y_AXIS]+=count_direction[Y_AXIS];
- WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
-
- #ifdef Y_DUAL_STEPPER_DRIVERS
- WRITE(Y2_STEP_PIN, INVERT_Y_STEP_PIN);
- #endif
- }
- counter_z += current_block->steps_z;
- if (counter_z > 0) {
- WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
-
- #ifdef Z_DUAL_STEPPER_DRIVERS
- WRITE(Z2_STEP_PIN, !INVERT_Z_STEP_PIN);
- #endif
- counter_z -= current_block->step_event_count;
- count_position[Z_AXIS]+=count_direction[Z_AXIS];
- WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN);
-
- #ifdef Z_DUAL_STEPPER_DRIVERS
- WRITE(Z2_STEP_PIN, INVERT_Z_STEP_PIN);
- #endif
- }
- #ifndef ADVANCE
- counter_e += current_block->steps_e;
- if (counter_e > 0) {
- WRITE_E_STEP(!INVERT_E_STEP_PIN);
- counter_e -= current_block->step_event_count;
- count_position[E_AXIS]+=count_direction[E_AXIS];
- WRITE_E_STEP(INVERT_E_STEP_PIN);
- }
- #endif
- step_events_completed += 1;
- if(step_events_completed >= current_block->step_event_count) break;
- }
-
- unsigned short timer;
- unsigned short step_rate;
- if (step_events_completed <= (unsigned long int)current_block->accelerate_until) {
- MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
- acc_step_rate += current_block->initial_rate;
-
- if(acc_step_rate > current_block->nominal_rate)
- acc_step_rate = current_block->nominal_rate;
-
- timer = calc_timer(acc_step_rate);
- OCR1A = timer;
- acceleration_time += timer;
- #ifdef ADVANCE
- for(int8_t i=0; i < step_loops; i++) {
- advance += advance_rate;
- }
-
-
- e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
- old_advance = advance >>8;
- #endif
- }
- else if (step_events_completed > (unsigned long int)current_block->decelerate_after) {
- MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate);
- if(step_rate > acc_step_rate) {
- step_rate = current_block->final_rate;
- }
- else {
- step_rate = acc_step_rate - step_rate;
- }
-
- if(step_rate < current_block->final_rate)
- step_rate = current_block->final_rate;
-
- timer = calc_timer(step_rate);
- OCR1A = timer;
- deceleration_time += timer;
- #ifdef ADVANCE
- for(int8_t i=0; i < step_loops; i++) {
- advance -= advance_rate;
- }
- if(advance < final_advance) advance = final_advance;
-
- e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
- old_advance = advance >>8;
- #endif
- }
- else {
- OCR1A = OCR1A_nominal;
-
- step_loops = step_loops_nominal;
- }
-
- if (step_events_completed >= current_block->step_event_count) {
- current_block = NULL;
- plan_discard_current_block();
- }
- }
- }
- #ifdef ADVANCE
- unsigned char old_OCR0A;
-
-
- ISR(TIMER0_COMPA_vect)
- {
- old_OCR0A += 52;
- OCR0A = old_OCR0A;
-
- for(unsigned char i=0; i<4;i++) {
- if (e_steps[0] != 0) {
- WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN);
- if (e_steps[0] < 0) {
- WRITE(E0_DIR_PIN, INVERT_E0_DIR);
- e_steps[0]++;
- WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
- }
- else if (e_steps[0] > 0) {
- WRITE(E0_DIR_PIN, !INVERT_E0_DIR);
- e_steps[0]--;
- WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
- }
- }
- #if EXTRUDERS > 1
- if (e_steps[1] != 0) {
- WRITE(E1_STEP_PIN, INVERT_E_STEP_PIN);
- if (e_steps[1] < 0) {
- WRITE(E1_DIR_PIN, INVERT_E1_DIR);
- e_steps[1]++;
- WRITE(E1_STEP_PIN, !INVERT_E_STEP_PIN);
- }
- else if (e_steps[1] > 0) {
- WRITE(E1_DIR_PIN, !INVERT_E1_DIR);
- e_steps[1]--;
- WRITE(E1_STEP_PIN, !INVERT_E_STEP_PIN);
- }
- }
- #endif
- #if EXTRUDERS > 2
- if (e_steps[2] != 0) {
- WRITE(E2_STEP_PIN, INVERT_E_STEP_PIN);
- if (e_steps[2] < 0) {
- WRITE(E2_DIR_PIN, INVERT_E2_DIR);
- e_steps[2]++;
- WRITE(E2_STEP_PIN, !INVERT_E_STEP_PIN);
- }
- else if (e_steps[2] > 0) {
- WRITE(E2_DIR_PIN, !INVERT_E2_DIR);
- e_steps[2]--;
- WRITE(E2_STEP_PIN, !INVERT_E_STEP_PIN);
- }
- }
- #endif
- }
- }
- #endif
- void st_init()
- {
- digipot_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
-
- #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(X_STEP_PIN) && (X_STEP_PIN > -1)
- SET_OUTPUT(X_STEP_PIN);
- WRITE(X_STEP_PIN,INVERT_X_STEP_PIN);
- 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);
- #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 ADVANCE
- #if defined(TCCR0A) && defined(WGM01)
- TCCR0A &= ~(1<<WGM01);
- TCCR0A &= ~(1<<WGM00);
- #endif
- e_steps[0] = 0;
- e_steps[1] = 0;
- e_steps[2] = 0;
- TIMSK0 |= (1<<OCIE0A);
- #endif
- enable_endstops(true);
- sei();
- }
- void st_synchronize()
- {
- while( blocks_queued()) {
- manage_heater();
-
- manage_inactivity(true);
- lcd_update();
- }
- }
- 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;
- }
- 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;
- 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);
- {
- volatile float x=1./float(axis+1)/float(axis+2);
- }
- WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
-
- 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);
- {
- volatile float x=1./float(axis+1)/float(axis+2);
- }
- WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
-
- 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
-
- {
- volatile float x=1./float(axis+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
- void digitalPotWrite(int address, int value)
- {
- #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
- 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 digipot_init()
- {
- EEPROM_read_st(EEPROM_SILENT,(uint8_t*)&SilentMode,sizeof(SilentMode));
- #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
- if(SilentMode == 0){
- const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT_LOUD;
- }else{
- const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT;
- }
- SPI.begin();
- pinMode(DIGIPOTSS_PIN, OUTPUT);
- for(int i=0;i<=4;i++)
-
- digipot_current(i,digipot_motor_current[i]);
- #endif
- #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 == 0){
- 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];
- }
- digipot_current(0, motor_current_setting[0]);
- digipot_current(1, motor_current_setting[1]);
- digipot_current(2, motor_current_setting[2]);
-
- TCCR5B = (TCCR5B & ~(_BV(CS50) | _BV(CS51) | _BV(CS52))) | _BV(CS50);
- #endif
- }
- void digipot_current(uint8_t driver, int current)
- {
- #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
- const uint8_t digipot_ch[] = DIGIPOT_CHANNELS;
- digitalPotWrite(digipot_ch[driver], current);
- #endif
- #ifdef MOTOR_CURRENT_PWM_XY_PIN
- 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);
- #endif
- }
- void microstep_init()
- {
- const uint8_t microstep_modes[] = MICROSTEP_MODES;
- #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
- 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
- }
- 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
- }
|