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.

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