My Marlin configs for Fabrikator Mini and CTC i3 Pro B
You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

stepper.cpp 21KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691
  1. /*
  2. stepper.c - stepper motor driver: executes motion plans using stepper motors
  3. Part of Grbl
  4. Copyright (c) 2009-2011 Simen Svale Skogsrud
  5. Grbl is free software: you can redistribute it and/or modify
  6. it under the terms of the GNU General Public License as published by
  7. the Free Software Foundation, either version 3 of the License, or
  8. (at your option) any later version.
  9. Grbl is distributed in the hope that it will be useful,
  10. but WITHOUT ANY WARRANTY; without even the implied warranty of
  11. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  12. GNU General Public License for more details.
  13. You should have received a copy of the GNU General Public License
  14. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
  15. */
  16. /* The timer calculations of this module informed by the 'RepRap cartesian firmware' by Zack Smith
  17. and Philipp Tiefenbacher. */
  18. #include "stepper.h"
  19. #include "Configuration.h"
  20. #include "Marlin.h"
  21. #include "planner.h"
  22. #include "pins.h"
  23. #include "fastio.h"
  24. #include "temperature.h"
  25. #include "ultralcd.h"
  26. #include "speed_lookuptable.h"
  27. //===========================================================================
  28. //=============================public variables ============================
  29. //===========================================================================
  30. block_t *current_block; // A pointer to the block currently being traced
  31. //===========================================================================
  32. //=============================private variables ============================
  33. //===========================================================================
  34. //static makes it inpossible to be called from outside of this file by extern.!
  35. // Variables used by The Stepper Driver Interrupt
  36. static unsigned char out_bits; // The next stepping-bits to be output
  37. static long counter_x, // Counter variables for the bresenham line tracer
  38. counter_y,
  39. counter_z,
  40. counter_e;
  41. volatile static unsigned long step_events_completed; // The number of step events executed in the current block
  42. #ifdef ADVANCE
  43. static long advance_rate, advance, final_advance = 0;
  44. static short old_advance = 0;
  45. #endif
  46. static short e_steps;
  47. static unsigned char busy = false; // TRUE when SIG_OUTPUT_COMPARE1A is being serviced. Used to avoid retriggering that handler.
  48. static long acceleration_time, deceleration_time;
  49. //static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
  50. static unsigned short acc_step_rate; // needed for deccelaration start point
  51. static char step_loops;
  52. static unsigned short OCR1A_nominal;
  53. volatile long endstops_trigsteps[3]={0,0,0};
  54. volatile long endstops_stepsTotal,endstops_stepsDone;
  55. static volatile bool endstop_x_hit=false;
  56. static volatile bool endstop_y_hit=false;
  57. static volatile bool endstop_z_hit=false;
  58. static bool old_x_min_endstop=false;
  59. static bool old_x_max_endstop=false;
  60. static bool old_y_min_endstop=false;
  61. static bool old_y_max_endstop=false;
  62. static bool old_z_min_endstop=false;
  63. static bool old_z_max_endstop=false;
  64. volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0};
  65. volatile char count_direction[NUM_AXIS] = { 1, 1, 1, 1};
  66. //===========================================================================
  67. //=============================functions ============================
  68. //===========================================================================
  69. // intRes = intIn1 * intIn2 >> 16
  70. // uses:
  71. // r26 to store 0
  72. // r27 to store the byte 1 of the 24 bit result
  73. #define MultiU16X8toH16(intRes, charIn1, intIn2) \
  74. asm volatile ( \
  75. "clr r26 \n\t" \
  76. "mul %A1, %B2 \n\t" \
  77. "movw %A0, r0 \n\t" \
  78. "mul %A1, %A2 \n\t" \
  79. "add %A0, r1 \n\t" \
  80. "adc %B0, r26 \n\t" \
  81. "lsr r0 \n\t" \
  82. "adc %A0, r26 \n\t" \
  83. "adc %B0, r26 \n\t" \
  84. "clr r1 \n\t" \
  85. : \
  86. "=&r" (intRes) \
  87. : \
  88. "d" (charIn1), \
  89. "d" (intIn2) \
  90. : \
  91. "r26" \
  92. )
  93. // intRes = longIn1 * longIn2 >> 24
  94. // uses:
  95. // r26 to store 0
  96. // r27 to store the byte 1 of the 48bit result
  97. #define MultiU24X24toH16(intRes, longIn1, longIn2) \
  98. asm volatile ( \
  99. "clr r26 \n\t" \
  100. "mul %A1, %B2 \n\t" \
  101. "mov r27, r1 \n\t" \
  102. "mul %B1, %C2 \n\t" \
  103. "movw %A0, r0 \n\t" \
  104. "mul %C1, %C2 \n\t" \
  105. "add %B0, r0 \n\t" \
  106. "mul %C1, %B2 \n\t" \
  107. "add %A0, r0 \n\t" \
  108. "adc %B0, r1 \n\t" \
  109. "mul %A1, %C2 \n\t" \
  110. "add r27, r0 \n\t" \
  111. "adc %A0, r1 \n\t" \
  112. "adc %B0, r26 \n\t" \
  113. "mul %B1, %B2 \n\t" \
  114. "add r27, r0 \n\t" \
  115. "adc %A0, r1 \n\t" \
  116. "adc %B0, r26 \n\t" \
  117. "mul %C1, %A2 \n\t" \
  118. "add r27, r0 \n\t" \
  119. "adc %A0, r1 \n\t" \
  120. "adc %B0, r26 \n\t" \
  121. "mul %B1, %A2 \n\t" \
  122. "add r27, r1 \n\t" \
  123. "adc %A0, r26 \n\t" \
  124. "adc %B0, r26 \n\t" \
  125. "lsr r27 \n\t" \
  126. "adc %A0, r26 \n\t" \
  127. "adc %B0, r26 \n\t" \
  128. "clr r1 \n\t" \
  129. : \
  130. "=&r" (intRes) \
  131. : \
  132. "d" (longIn1), \
  133. "d" (longIn2) \
  134. : \
  135. "r26" , "r27" \
  136. )
  137. // Some useful constants
  138. #define ENABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 |= (1<<OCIE1A)
  139. #define DISABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 &= ~(1<<OCIE1A)
  140. void checkHitEndstops()
  141. {
  142. if( endstop_x_hit || endstop_y_hit || endstop_z_hit) {
  143. SERIAL_ECHO_START;
  144. SERIAL_ECHOPGM("endstops hit: ");
  145. if(endstop_x_hit) {
  146. SERIAL_ECHOPAIR(" X:",(float)endstops_trigsteps[X_AXIS]/axis_steps_per_unit[X_AXIS]);
  147. }
  148. if(endstop_y_hit) {
  149. SERIAL_ECHOPAIR(" Y:",(float)endstops_trigsteps[Y_AXIS]/axis_steps_per_unit[Y_AXIS]);
  150. }
  151. if(endstop_z_hit) {
  152. SERIAL_ECHOPAIR(" Z:",(float)endstops_trigsteps[Z_AXIS]/axis_steps_per_unit[Z_AXIS]);
  153. }
  154. SERIAL_ECHOLN("");
  155. endstop_x_hit=false;
  156. endstop_y_hit=false;
  157. endstop_z_hit=false;
  158. }
  159. }
  160. void endstops_hit_on_purpose()
  161. {
  162. endstop_x_hit=false;
  163. endstop_y_hit=false;
  164. endstop_z_hit=false;
  165. }
  166. // __________________________
  167. // /| |\ _________________ ^
  168. // / | | \ /| |\ |
  169. // / | | \ / | | \ s
  170. // / | | | | | \ p
  171. // / | | | | | \ e
  172. // +-----+------------------------+---+--+---------------+----+ e
  173. // | BLOCK 1 | BLOCK 2 | d
  174. //
  175. // time ----->
  176. //
  177. // The trapezoid is the shape the speed curve over time. It starts at block->initial_rate, accelerates
  178. // first block->accelerate_until step_events_completed, then keeps going at constant speed until
  179. // step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset.
  180. // The slope of acceleration is calculated with the leib ramp alghorithm.
  181. void st_wake_up() {
  182. // TCNT1 = 0;
  183. if(busy == false)
  184. ENABLE_STEPPER_DRIVER_INTERRUPT();
  185. }
  186. FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) {
  187. unsigned short timer;
  188. if(step_rate > MAX_STEP_FREQUENCY) step_rate = MAX_STEP_FREQUENCY;
  189. if(step_rate > 20000) { // If steprate > 20kHz >> step 4 times
  190. step_rate = (step_rate >> 2)&0x3fff;
  191. step_loops = 4;
  192. }
  193. else if(step_rate > 10000) { // If steprate > 10kHz >> step 2 times
  194. step_rate = (step_rate >> 1)&0x7fff;
  195. step_loops = 2;
  196. }
  197. else {
  198. step_loops = 1;
  199. }
  200. if(step_rate < 32) step_rate = 32;
  201. step_rate -= 32; // Correct for minimal speed
  202. if(step_rate >= (8*256)){ // higher step rate
  203. unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate>>8)][0];
  204. unsigned char tmp_step_rate = (step_rate & 0x00ff);
  205. unsigned short gain = (unsigned short)pgm_read_word_near(table_address+2);
  206. MultiU16X8toH16(timer, tmp_step_rate, gain);
  207. timer = (unsigned short)pgm_read_word_near(table_address) - timer;
  208. }
  209. else { // lower step rates
  210. unsigned short table_address = (unsigned short)&speed_lookuptable_slow[0][0];
  211. table_address += ((step_rate)>>1) & 0xfffc;
  212. timer = (unsigned short)pgm_read_word_near(table_address);
  213. timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
  214. }
  215. if(timer < 100) { timer = 100; MSerial.print("Steprate to high : "); MSerial.println(step_rate); }//(20kHz this should never happen)
  216. return timer;
  217. }
  218. // Initializes the trapezoid generator from the current block. Called whenever a new
  219. // block begins.
  220. FORCE_INLINE void trapezoid_generator_reset() {
  221. #ifdef ADVANCE
  222. advance = current_block->initial_advance;
  223. final_advance = current_block->final_advance;
  224. #endif
  225. deceleration_time = 0;
  226. // step_rate to timer interval
  227. acc_step_rate = current_block->initial_rate;
  228. acceleration_time = calc_timer(acc_step_rate);
  229. OCR1A = acceleration_time;
  230. OCR1A_nominal = calc_timer(current_block->nominal_rate);
  231. }
  232. // "The Stepper Driver Interrupt" - This timer interrupt is the workhorse.
  233. // It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately.
  234. ISR(TIMER1_COMPA_vect)
  235. {
  236. // If there is no current block, attempt to pop one from the buffer
  237. if (current_block == NULL) {
  238. // Anything in the buffer?
  239. current_block = plan_get_current_block();
  240. if (current_block != NULL) {
  241. trapezoid_generator_reset();
  242. counter_x = -(current_block->step_event_count >> 1);
  243. counter_y = counter_x;
  244. counter_z = counter_x;
  245. counter_e = counter_x;
  246. step_events_completed = 0;
  247. // #ifdef ADVANCE
  248. e_steps = 0;
  249. // #endif
  250. }
  251. else {
  252. OCR1A=2000; // 1kHz.
  253. }
  254. }
  255. if (current_block != NULL) {
  256. // Set directions TO DO This should be done once during init of trapezoid. Endstops -> interrupt
  257. out_bits = current_block->direction_bits;
  258. // Set direction en check limit switches
  259. if ((out_bits & (1<<X_AXIS)) != 0) { // -direction
  260. WRITE(X_DIR_PIN, INVERT_X_DIR);
  261. count_direction[X_AXIS]=-1;
  262. #if X_MIN_PIN > -1
  263. bool x_min_endstop=(READ(X_MIN_PIN) != X_ENDSTOPS_INVERTING);
  264. if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
  265. endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
  266. endstop_x_hit=true;
  267. step_events_completed = current_block->step_event_count;
  268. }
  269. old_x_min_endstop = x_min_endstop;
  270. #endif
  271. }
  272. else { // +direction
  273. WRITE(X_DIR_PIN,!INVERT_X_DIR);
  274. count_direction[X_AXIS]=1;
  275. #if X_MAX_PIN > -1
  276. bool x_max_endstop=(READ(X_MAX_PIN) != X_ENDSTOPS_INVERTING);
  277. if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
  278. endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
  279. endstop_x_hit=true;
  280. step_events_completed = current_block->step_event_count;
  281. }
  282. old_x_max_endstop = x_max_endstop;
  283. #endif
  284. }
  285. if ((out_bits & (1<<Y_AXIS)) != 0) { // -direction
  286. WRITE(Y_DIR_PIN,INVERT_Y_DIR);
  287. count_direction[Y_AXIS]=-1;
  288. #if Y_MIN_PIN > -1
  289. bool y_min_endstop=(READ(Y_MIN_PIN) != Y_ENDSTOPS_INVERTING);
  290. if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
  291. endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
  292. endstop_y_hit=true;
  293. step_events_completed = current_block->step_event_count;
  294. }
  295. old_y_min_endstop = y_min_endstop;
  296. #endif
  297. }
  298. else { // +direction
  299. WRITE(Y_DIR_PIN,!INVERT_Y_DIR);
  300. count_direction[Y_AXIS]=1;
  301. #if Y_MAX_PIN > -1
  302. bool y_max_endstop=(READ(Y_MAX_PIN) != Y_ENDSTOPS_INVERTING);
  303. if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
  304. endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
  305. endstop_y_hit=true;
  306. step_events_completed = current_block->step_event_count;
  307. }
  308. old_y_max_endstop = y_max_endstop;
  309. #endif
  310. }
  311. if ((out_bits & (1<<Z_AXIS)) != 0) { // -direction
  312. WRITE(Z_DIR_PIN,INVERT_Z_DIR);
  313. count_direction[Z_AXIS]=-1;
  314. #if Z_MIN_PIN > -1
  315. bool z_min_endstop=(READ(Z_MIN_PIN) != Z_ENDSTOPS_INVERTING);
  316. if(z_min_endstop && old_z_min_endstop && (current_block->steps_z > 0)) {
  317. endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
  318. endstop_z_hit=true;
  319. step_events_completed = current_block->step_event_count;
  320. }
  321. old_z_min_endstop = z_min_endstop;
  322. #endif
  323. }
  324. else { // +direction
  325. WRITE(Z_DIR_PIN,!INVERT_Z_DIR);
  326. count_direction[Z_AXIS]=1;
  327. #if Z_MAX_PIN > -1
  328. bool z_max_endstop=(READ(Z_MAX_PIN) != Z_ENDSTOPS_INVERTING);
  329. if(z_max_endstop && old_z_max_endstop && (current_block->steps_z > 0)) {
  330. endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
  331. endstop_z_hit=true;
  332. step_events_completed = current_block->step_event_count;
  333. }
  334. old_z_max_endstop = z_max_endstop;
  335. #endif
  336. }
  337. #ifndef ADVANCE
  338. if ((out_bits & (1<<E_AXIS)) != 0) { // -direction
  339. WRITE(E_DIR_PIN,INVERT_E_DIR);
  340. count_direction[E_AXIS]=-1;
  341. }
  342. else { // +direction
  343. WRITE(E_DIR_PIN,!INVERT_E_DIR);
  344. count_direction[E_AXIS]=-1;
  345. }
  346. #endif //!ADVANCE
  347. for(int8_t i=0; i < step_loops; i++) { // Take multiple steps per interrupt (For high speed moves)
  348. MSerial.checkRx();
  349. /*
  350. counter_e += current_block->steps_e;
  351. if (counter_e > 0) {
  352. counter_e -= current_block->step_event_count;
  353. if ((out_bits & (1<<E_AXIS)) != 0) { // - direction
  354. CRITICAL_SECTION_START;
  355. e_steps--;
  356. CRITICAL_SECTION_END;
  357. }
  358. else {
  359. CRITICAL_SECTION_START;
  360. e_steps++;
  361. CRITICAL_SECTION_END;
  362. }
  363. }
  364. */
  365. /*
  366. // Do E steps + advance steps
  367. CRITICAL_SECTION_START;
  368. e_steps += ((advance >> 16) - old_advance);
  369. CRITICAL_SECTION_END;
  370. old_advance = advance >> 16;
  371. */
  372. counter_x += current_block->steps_x;
  373. if (counter_x > 0) {
  374. WRITE(X_STEP_PIN, HIGH);
  375. counter_x -= current_block->step_event_count;
  376. WRITE(X_STEP_PIN, LOW);
  377. count_position[X_AXIS]+=count_direction[X_AXIS];
  378. }
  379. counter_y += current_block->steps_y;
  380. if (counter_y > 0) {
  381. WRITE(Y_STEP_PIN, HIGH);
  382. counter_y -= current_block->step_event_count;
  383. WRITE(Y_STEP_PIN, LOW);
  384. count_position[Y_AXIS]+=count_direction[Y_AXIS];
  385. }
  386. counter_z += current_block->steps_z;
  387. if (counter_z > 0) {
  388. WRITE(Z_STEP_PIN, HIGH);
  389. counter_z -= current_block->step_event_count;
  390. WRITE(Z_STEP_PIN, LOW);
  391. count_position[Z_AXIS]+=count_direction[Z_AXIS];
  392. }
  393. #ifndef ADVANCE
  394. counter_e += current_block->steps_e;
  395. if (counter_e > 0) {
  396. WRITE(E_STEP_PIN, HIGH);
  397. counter_e -= current_block->step_event_count;
  398. WRITE(E_STEP_PIN, LOW);
  399. count_position[E_AXIS]+=count_direction[E_AXIS];
  400. }
  401. #endif //!ADVANCE
  402. step_events_completed += 1;
  403. if(step_events_completed >= current_block->step_event_count) break;
  404. }
  405. // Calculare new timer value
  406. unsigned short timer;
  407. unsigned short step_rate;
  408. if (step_events_completed <= current_block->accelerate_until) {
  409. MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
  410. acc_step_rate += current_block->initial_rate;
  411. // upper limit
  412. if(acc_step_rate > current_block->nominal_rate)
  413. acc_step_rate = current_block->nominal_rate;
  414. // step_rate to timer interval
  415. timer = calc_timer(acc_step_rate);
  416. OCR1A = timer;
  417. acceleration_time += timer;
  418. #ifdef ADVANCE
  419. advance += advance_rate;
  420. #endif
  421. }
  422. else if (step_events_completed > current_block->decelerate_after) {
  423. MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate);
  424. if(step_rate > acc_step_rate) { // Check step_rate stays positive
  425. step_rate = current_block->final_rate;
  426. }
  427. else {
  428. step_rate = acc_step_rate - step_rate; // Decelerate from aceleration end point.
  429. }
  430. // lower limit
  431. if(step_rate < current_block->final_rate)
  432. step_rate = current_block->final_rate;
  433. // step_rate to timer interval
  434. timer = calc_timer(step_rate);
  435. OCR1A = timer;
  436. deceleration_time += timer;
  437. #ifdef ADVANCE
  438. advance -= advance_rate;
  439. if(advance < final_advance)
  440. advance = final_advance;
  441. #endif //ADVANCE
  442. }
  443. else {
  444. OCR1A = OCR1A_nominal;
  445. }
  446. // If current block is finished, reset pointer
  447. if (step_events_completed >= current_block->step_event_count) {
  448. current_block = NULL;
  449. plan_discard_current_block();
  450. }
  451. }
  452. }
  453. #ifdef ADVANCE
  454. unsigned char old_OCR0A;
  455. // Timer interrupt for E. e_steps is set in the main routine;
  456. // Timer 0 is shared with millies
  457. ISR(TIMER0_COMPA_vect)
  458. {
  459. // Critical section needed because Timer 1 interrupt has higher priority.
  460. // The pin set functions are placed on trategic position to comply with the stepper driver timing.
  461. WRITE(E_STEP_PIN, LOW);
  462. // Set E direction (Depends on E direction + advance)
  463. if (e_steps < 0) {
  464. WRITE(E_DIR_PIN,INVERT_E_DIR);
  465. e_steps++;
  466. WRITE(E_STEP_PIN, HIGH);
  467. }
  468. if (e_steps > 0) {
  469. WRITE(E_DIR_PIN,!INVERT_E_DIR);
  470. e_steps--;
  471. WRITE(E_STEP_PIN, HIGH);
  472. }
  473. old_OCR0A += 25; // 10kHz interrupt
  474. OCR0A = old_OCR0A;
  475. }
  476. #endif // ADVANCE
  477. void st_init()
  478. {
  479. //Initialize Dir Pins
  480. #if X_DIR_PIN > -1
  481. SET_OUTPUT(X_DIR_PIN);
  482. #endif
  483. #if Y_DIR_PIN > -1
  484. SET_OUTPUT(Y_DIR_PIN);
  485. #endif
  486. #if Z_DIR_PIN > -1
  487. SET_OUTPUT(Z_DIR_PIN);
  488. #endif
  489. #if E_DIR_PIN > -1
  490. SET_OUTPUT(E_DIR_PIN);
  491. #endif
  492. //Initialize Enable Pins - steppers default to disabled.
  493. #if (X_ENABLE_PIN > -1)
  494. SET_OUTPUT(X_ENABLE_PIN);
  495. if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
  496. #endif
  497. #if (Y_ENABLE_PIN > -1)
  498. SET_OUTPUT(Y_ENABLE_PIN);
  499. if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
  500. #endif
  501. #if (Z_ENABLE_PIN > -1)
  502. SET_OUTPUT(Z_ENABLE_PIN);
  503. if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
  504. #endif
  505. #if (E_ENABLE_PIN > -1)
  506. SET_OUTPUT(E_ENABLE_PIN);
  507. if(!E_ENABLE_ON) WRITE(E_ENABLE_PIN,HIGH);
  508. #endif
  509. //endstops and pullups
  510. #ifdef ENDSTOPPULLUPS
  511. #if X_MIN_PIN > -1
  512. SET_INPUT(X_MIN_PIN);
  513. WRITE(X_MIN_PIN,HIGH);
  514. #endif
  515. #if X_MAX_PIN > -1
  516. SET_INPUT(X_MAX_PIN);
  517. WRITE(X_MAX_PIN,HIGH);
  518. #endif
  519. #if Y_MIN_PIN > -1
  520. SET_INPUT(Y_MIN_PIN);
  521. WRITE(Y_MIN_PIN,HIGH);
  522. #endif
  523. #if Y_MAX_PIN > -1
  524. SET_INPUT(Y_MAX_PIN);
  525. WRITE(Y_MAX_PIN,HIGH);
  526. #endif
  527. #if Z_MIN_PIN > -1
  528. SET_INPUT(Z_MIN_PIN);
  529. WRITE(Z_MIN_PIN,HIGH);
  530. #endif
  531. #if Z_MAX_PIN > -1
  532. SET_INPUT(Z_MAX_PIN);
  533. WRITE(Z_MAX_PIN,HIGH);
  534. #endif
  535. #else //ENDSTOPPULLUPS
  536. #if X_MIN_PIN > -1
  537. SET_INPUT(X_MIN_PIN);
  538. #endif
  539. #if X_MAX_PIN > -1
  540. SET_INPUT(X_MAX_PIN);
  541. #endif
  542. #if Y_MIN_PIN > -1
  543. SET_INPUT(Y_MIN_PIN);
  544. #endif
  545. #if Y_MAX_PIN > -1
  546. SET_INPUT(Y_MAX_PIN);
  547. #endif
  548. #if Z_MIN_PIN > -1
  549. SET_INPUT(Z_MIN_PIN);
  550. #endif
  551. #if Z_MAX_PIN > -1
  552. SET_INPUT(Z_MAX_PIN);
  553. #endif
  554. #endif //ENDSTOPPULLUPS
  555. //Initialize Step Pins
  556. #if (X_STEP_PIN > -1)
  557. SET_OUTPUT(X_STEP_PIN);
  558. #endif
  559. #if (Y_STEP_PIN > -1)
  560. SET_OUTPUT(Y_STEP_PIN);
  561. #endif
  562. #if (Z_STEP_PIN > -1)
  563. SET_OUTPUT(Z_STEP_PIN);
  564. #endif
  565. #if (E_STEP_PIN > -1)
  566. SET_OUTPUT(E_STEP_PIN);
  567. #endif
  568. // waveform generation = 0100 = CTC
  569. TCCR1B &= ~(1<<WGM13);
  570. TCCR1B |= (1<<WGM12);
  571. TCCR1A &= ~(1<<WGM11);
  572. TCCR1A &= ~(1<<WGM10);
  573. // output mode = 00 (disconnected)
  574. TCCR1A &= ~(3<<COM1A0);
  575. TCCR1A &= ~(3<<COM1B0);
  576. TCCR1B = (TCCR1B & ~(0x07<<CS10)) | (2<<CS10); // 2MHz timer
  577. OCR1A = 0x4000;
  578. TCNT1 = 0;
  579. ENABLE_STEPPER_DRIVER_INTERRUPT();
  580. #ifdef ADVANCE
  581. e_steps = 0;
  582. TIMSK0 |= (1<<OCIE0A);
  583. #endif //ADVANCE
  584. sei();
  585. }
  586. // Block until all buffered steps are executed
  587. void st_synchronize()
  588. {
  589. while(plan_get_current_block()) {
  590. manage_heater();
  591. manage_inactivity(1);
  592. LCD_STATUS;
  593. }
  594. }
  595. void st_set_position(const long &x, const long &y, const long &z, const long &e)
  596. {
  597. CRITICAL_SECTION_START;
  598. count_position[X_AXIS] = x;
  599. count_position[Y_AXIS] = y;
  600. count_position[Z_AXIS] = z;
  601. count_position[E_AXIS] = e;
  602. CRITICAL_SECTION_END;
  603. }
  604. void st_set_e_position(const long &e)
  605. {
  606. CRITICAL_SECTION_START;
  607. count_position[E_AXIS] = e;
  608. CRITICAL_SECTION_END;
  609. }
  610. long st_get_position(char axis)
  611. {
  612. long count_pos;
  613. CRITICAL_SECTION_START;
  614. count_pos = count_position[axis];
  615. CRITICAL_SECTION_END;
  616. return count_pos;
  617. }
  618. void finishAndDisableSteppers()
  619. {
  620. st_synchronize();
  621. LCD_MESSAGEPGM("Released.");
  622. disable_x();
  623. disable_y();
  624. disable_z();
  625. disable_e();
  626. }