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 33KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135
  1. /**
  2. * Marlin 3D Printer Firmware
  3. * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
  4. *
  5. * Based on Sprinter and grbl.
  6. * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
  7. *
  8. * This program is free software: you can redistribute it and/or modify
  9. * it under the terms of the GNU General Public License as published by
  10. * the Free Software Foundation, either version 3 of the License, or
  11. * (at your option) any later version.
  12. *
  13. * This program is distributed in the hope that it will be useful,
  14. * but WITHOUT ANY WARRANTY; without even the implied warranty of
  15. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  16. * GNU General Public License for more details.
  17. *
  18. * You should have received a copy of the GNU General Public License
  19. * along with this program. If not, see <http://www.gnu.org/licenses/>.
  20. *
  21. */
  22. /**
  23. * stepper.cpp - A singleton object to execute motion plans using stepper motors
  24. * Marlin Firmware
  25. *
  26. * Derived from Grbl
  27. * Copyright (c) 2009-2011 Simen Svale Skogsrud
  28. *
  29. * Grbl is free software: you can redistribute it and/or modify
  30. * it under the terms of the GNU General Public License as published by
  31. * the Free Software Foundation, either version 3 of the License, or
  32. * (at your option) any later version.
  33. *
  34. * Grbl is distributed in the hope that it will be useful,
  35. * but WITHOUT ANY WARRANTY; without even the implied warranty of
  36. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  37. * GNU General Public License for more details.
  38. *
  39. * You should have received a copy of the GNU General Public License
  40. * along with Grbl. If not, see <http://www.gnu.org/licenses/>.
  41. */
  42. /* The timer calculations of this module informed by the 'RepRap cartesian firmware' by Zack Smith
  43. and Philipp Tiefenbacher. */
  44. #include "Marlin.h"
  45. #include "stepper.h"
  46. #include "endstops.h"
  47. #include "planner.h"
  48. #include "temperature.h"
  49. #include "ultralcd.h"
  50. #include "language.h"
  51. #include "cardreader.h"
  52. #include "speed_lookuptable.h"
  53. #if HAS_DIGIPOTSS
  54. #include <SPI.h>
  55. #endif
  56. Stepper stepper; // Singleton
  57. // public:
  58. block_t* Stepper::current_block = NULL; // A pointer to the block currently being traced
  59. #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
  60. bool Stepper::abort_on_endstop_hit = false;
  61. #endif
  62. #if ENABLED(Z_DUAL_ENDSTOPS)
  63. bool Stepper::performing_homing = false;
  64. #endif
  65. // private:
  66. unsigned char Stepper::last_direction_bits = 0; // The next stepping-bits to be output
  67. unsigned int Stepper::cleaning_buffer_counter = 0;
  68. #if ENABLED(Z_DUAL_ENDSTOPS)
  69. bool Stepper::locked_z_motor = false;
  70. bool Stepper::locked_z2_motor = false;
  71. #endif
  72. long Stepper::counter_X = 0,
  73. Stepper::counter_Y = 0,
  74. Stepper::counter_Z = 0,
  75. Stepper::counter_E = 0;
  76. volatile unsigned long Stepper::step_events_completed = 0; // The number of step events executed in the current block
  77. #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE)
  78. unsigned char Stepper::old_OCR0A;
  79. volatile unsigned char Stepper::eISR_Rate = 200; // Keep the ISR at a low rate until needed
  80. #if ENABLED(LIN_ADVANCE)
  81. volatile int Stepper::e_steps[EXTRUDERS];
  82. int Stepper::extruder_advance_k = LIN_ADVANCE_K,
  83. Stepper::final_estep_rate,
  84. Stepper::current_estep_rate[EXTRUDERS],
  85. Stepper::current_adv_steps[EXTRUDERS];
  86. #else
  87. long Stepper::e_steps[EXTRUDERS],
  88. Stepper::final_advance = 0,
  89. Stepper::old_advance = 0,
  90. Stepper::advance_rate,
  91. Stepper::advance;
  92. #endif
  93. #endif
  94. long Stepper::acceleration_time, Stepper::deceleration_time;
  95. volatile long Stepper::count_position[NUM_AXIS] = { 0 };
  96. volatile signed char Stepper::count_direction[NUM_AXIS] = { 1, 1, 1, 1 };
  97. unsigned short Stepper::acc_step_rate; // needed for deceleration start point
  98. uint8_t Stepper::step_loops, Stepper::step_loops_nominal;
  99. unsigned short Stepper::OCR1A_nominal;
  100. volatile long Stepper::endstops_trigsteps[3];
  101. #if ENABLED(DUAL_X_CARRIAGE)
  102. #define X_APPLY_DIR(v,ALWAYS) \
  103. if (extruder_duplication_enabled || ALWAYS) { \
  104. X_DIR_WRITE(v); \
  105. X2_DIR_WRITE(v); \
  106. } \
  107. else { \
  108. if (current_block->active_extruder) X2_DIR_WRITE(v); else X_DIR_WRITE(v); \
  109. }
  110. #define X_APPLY_STEP(v,ALWAYS) \
  111. if (extruder_duplication_enabled || ALWAYS) { \
  112. X_STEP_WRITE(v); \
  113. X2_STEP_WRITE(v); \
  114. } \
  115. else { \
  116. if (current_block->active_extruder != 0) X2_STEP_WRITE(v); else X_STEP_WRITE(v); \
  117. }
  118. #else
  119. #define X_APPLY_DIR(v,Q) X_DIR_WRITE(v)
  120. #define X_APPLY_STEP(v,Q) X_STEP_WRITE(v)
  121. #endif
  122. #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
  123. #define Y_APPLY_DIR(v,Q) { Y_DIR_WRITE(v); Y2_DIR_WRITE((v) != INVERT_Y2_VS_Y_DIR); }
  124. #define Y_APPLY_STEP(v,Q) { Y_STEP_WRITE(v); Y2_STEP_WRITE(v); }
  125. #else
  126. #define Y_APPLY_DIR(v,Q) Y_DIR_WRITE(v)
  127. #define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v)
  128. #endif
  129. #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
  130. #define Z_APPLY_DIR(v,Q) { Z_DIR_WRITE(v); Z2_DIR_WRITE(v); }
  131. #if ENABLED(Z_DUAL_ENDSTOPS)
  132. #define Z_APPLY_STEP(v,Q) \
  133. if (performing_homing) { \
  134. if (Z_HOME_DIR > 0) {\
  135. if (!(TEST(endstops.old_endstop_bits, Z_MAX) && (count_direction[Z_AXIS] > 0)) && !locked_z_motor) Z_STEP_WRITE(v); \
  136. if (!(TEST(endstops.old_endstop_bits, Z2_MAX) && (count_direction[Z_AXIS] > 0)) && !locked_z2_motor) Z2_STEP_WRITE(v); \
  137. } \
  138. else { \
  139. if (!(TEST(endstops.old_endstop_bits, Z_MIN) && (count_direction[Z_AXIS] < 0)) && !locked_z_motor) Z_STEP_WRITE(v); \
  140. if (!(TEST(endstops.old_endstop_bits, Z2_MIN) && (count_direction[Z_AXIS] < 0)) && !locked_z2_motor) Z2_STEP_WRITE(v); \
  141. } \
  142. } \
  143. else { \
  144. Z_STEP_WRITE(v); \
  145. Z2_STEP_WRITE(v); \
  146. }
  147. #else
  148. #define Z_APPLY_STEP(v,Q) { Z_STEP_WRITE(v); Z2_STEP_WRITE(v); }
  149. #endif
  150. #else
  151. #define Z_APPLY_DIR(v,Q) Z_DIR_WRITE(v)
  152. #define Z_APPLY_STEP(v,Q) Z_STEP_WRITE(v)
  153. #endif
  154. #define E_APPLY_STEP(v,Q) E_STEP_WRITE(v)
  155. // intRes = longIn1 * longIn2 >> 24
  156. // uses:
  157. // r26 to store 0
  158. // r27 to store bits 16-23 of the 48bit result. The top bit is used to round the two byte result.
  159. // note that the lower two bytes and the upper byte of the 48bit result are not calculated.
  160. // this can cause the result to be out by one as the lower bytes may cause carries into the upper ones.
  161. // B0 A0 are bits 24-39 and are the returned value
  162. // C1 B1 A1 is longIn1
  163. // D2 C2 B2 A2 is longIn2
  164. //
  165. #define MultiU24X32toH16(intRes, longIn1, longIn2) \
  166. asm volatile ( \
  167. "clr r26 \n\t" \
  168. "mul %A1, %B2 \n\t" \
  169. "mov r27, r1 \n\t" \
  170. "mul %B1, %C2 \n\t" \
  171. "movw %A0, r0 \n\t" \
  172. "mul %C1, %C2 \n\t" \
  173. "add %B0, r0 \n\t" \
  174. "mul %C1, %B2 \n\t" \
  175. "add %A0, r0 \n\t" \
  176. "adc %B0, r1 \n\t" \
  177. "mul %A1, %C2 \n\t" \
  178. "add r27, r0 \n\t" \
  179. "adc %A0, r1 \n\t" \
  180. "adc %B0, r26 \n\t" \
  181. "mul %B1, %B2 \n\t" \
  182. "add r27, r0 \n\t" \
  183. "adc %A0, r1 \n\t" \
  184. "adc %B0, r26 \n\t" \
  185. "mul %C1, %A2 \n\t" \
  186. "add r27, r0 \n\t" \
  187. "adc %A0, r1 \n\t" \
  188. "adc %B0, r26 \n\t" \
  189. "mul %B1, %A2 \n\t" \
  190. "add r27, r1 \n\t" \
  191. "adc %A0, r26 \n\t" \
  192. "adc %B0, r26 \n\t" \
  193. "lsr r27 \n\t" \
  194. "adc %A0, r26 \n\t" \
  195. "adc %B0, r26 \n\t" \
  196. "mul %D2, %A1 \n\t" \
  197. "add %A0, r0 \n\t" \
  198. "adc %B0, r1 \n\t" \
  199. "mul %D2, %B1 \n\t" \
  200. "add %B0, r0 \n\t" \
  201. "clr r1 \n\t" \
  202. : \
  203. "=&r" (intRes) \
  204. : \
  205. "d" (longIn1), \
  206. "d" (longIn2) \
  207. : \
  208. "r26" , "r27" \
  209. )
  210. // Some useful constants
  211. #define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A)
  212. #define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A)
  213. /**
  214. * __________________________
  215. * /| |\ _________________ ^
  216. * / | | \ /| |\ |
  217. * / | | \ / | | \ s
  218. * / | | | | | \ p
  219. * / | | | | | \ e
  220. * +-----+------------------------+---+--+---------------+----+ e
  221. * | BLOCK 1 | BLOCK 2 | d
  222. *
  223. * time ----->
  224. *
  225. * The trapezoid is the shape the speed curve over time. It starts at block->initial_rate, accelerates
  226. * first block->accelerate_until step_events_completed, then keeps going at constant speed until
  227. * step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset.
  228. * The slope of acceleration is calculated using v = u + at where t is the accumulated timer values of the steps so far.
  229. */
  230. void Stepper::wake_up() {
  231. // TCNT1 = 0;
  232. ENABLE_STEPPER_DRIVER_INTERRUPT();
  233. }
  234. /**
  235. * Set the stepper direction of each axis
  236. *
  237. * COREXY: X_AXIS=A_AXIS and Y_AXIS=B_AXIS
  238. * COREXZ: X_AXIS=A_AXIS and Z_AXIS=C_AXIS
  239. * COREYZ: Y_AXIS=B_AXIS and Z_AXIS=C_AXIS
  240. */
  241. void Stepper::set_directions() {
  242. #define SET_STEP_DIR(AXIS) \
  243. if (motor_direction(AXIS ##_AXIS)) { \
  244. AXIS ##_APPLY_DIR(INVERT_## AXIS ##_DIR, false); \
  245. count_direction[AXIS ##_AXIS] = -1; \
  246. } \
  247. else { \
  248. AXIS ##_APPLY_DIR(!INVERT_## AXIS ##_DIR, false); \
  249. count_direction[AXIS ##_AXIS] = 1; \
  250. }
  251. SET_STEP_DIR(X); // A
  252. SET_STEP_DIR(Y); // B
  253. SET_STEP_DIR(Z); // C
  254. #if DISABLED(ADVANCE)
  255. if (motor_direction(E_AXIS)) {
  256. REV_E_DIR();
  257. count_direction[E_AXIS] = -1;
  258. }
  259. else {
  260. NORM_E_DIR();
  261. count_direction[E_AXIS] = 1;
  262. }
  263. #endif //!ADVANCE
  264. }
  265. // "The Stepper Driver Interrupt" - This timer interrupt is the workhorse.
  266. // It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately.
  267. ISR(TIMER1_COMPA_vect) { Stepper::isr(); }
  268. void Stepper::isr() {
  269. if (cleaning_buffer_counter) {
  270. current_block = NULL;
  271. planner.discard_current_block();
  272. #ifdef SD_FINISHED_RELEASECOMMAND
  273. if ((cleaning_buffer_counter == 1) && (SD_FINISHED_STEPPERRELEASE)) enqueue_and_echo_commands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
  274. #endif
  275. cleaning_buffer_counter--;
  276. OCR1A = 200;
  277. return;
  278. }
  279. // If there is no current block, attempt to pop one from the buffer
  280. if (!current_block) {
  281. // Anything in the buffer?
  282. current_block = planner.get_current_block();
  283. if (current_block) {
  284. current_block->busy = true;
  285. trapezoid_generator_reset();
  286. counter_X = -(current_block->step_event_count >> 1);
  287. counter_Y = counter_Z = counter_E = counter_X;
  288. step_events_completed = 0;
  289. #if ENABLED(Z_LATE_ENABLE)
  290. if (current_block->steps[Z_AXIS] > 0) {
  291. enable_z();
  292. OCR1A = 2000; //1ms wait
  293. return;
  294. }
  295. #endif
  296. // #if ENABLED(ADVANCE)
  297. // e_steps[current_block->active_extruder] = 0;
  298. // #endif
  299. }
  300. else {
  301. OCR1A = 2000; // 1kHz.
  302. }
  303. }
  304. if (current_block != NULL) {
  305. // Update endstops state, if enabled
  306. #if HAS_BED_PROBE
  307. if (endstops.enabled || endstops.z_probe_enabled) endstops.update();
  308. #else
  309. if (endstops.enabled) endstops.update();
  310. #endif
  311. // Take multiple steps per interrupt (For high speed moves)
  312. for (int8_t i = 0; i < step_loops; i++) {
  313. #ifndef USBCON
  314. customizedSerial.checkRx(); // Check for serial chars.
  315. #endif
  316. #if ENABLED(LIN_ADVANCE)
  317. counter_E += current_block->steps[E_AXIS];
  318. if (counter_E > 0) {
  319. counter_E -= current_block->step_event_count;
  320. count_position[E_AXIS] += count_direction[E_AXIS];
  321. e_steps[current_block->active_extruder] += motor_direction(E_AXIS) ? -1 : 1;
  322. }
  323. if (current_block->use_advance_lead) {
  324. int delta_adv_steps; //Maybe a char would be enough?
  325. delta_adv_steps = (((long)extruder_advance_k * current_estep_rate[current_block->active_extruder]) >> 9) - current_adv_steps[current_block->active_extruder];
  326. e_steps[current_block->active_extruder] += delta_adv_steps;
  327. current_adv_steps[current_block->active_extruder] += delta_adv_steps;
  328. }
  329. #elif ENABLED(ADVANCE)
  330. counter_E += current_block->steps[E_AXIS];
  331. if (counter_E > 0) {
  332. counter_E -= current_block->step_event_count;
  333. e_steps[current_block->active_extruder] += motor_direction(E_AXIS) ? -1 : 1;
  334. }
  335. #endif // ADVANCE or LIN_ADVANCE
  336. #define _COUNTER(AXIS) counter_## AXIS
  337. #define _APPLY_STEP(AXIS) AXIS ##_APPLY_STEP
  338. #define _INVERT_STEP_PIN(AXIS) INVERT_## AXIS ##_STEP_PIN
  339. #define STEP_ADD(AXIS) \
  340. _COUNTER(AXIS) += current_block->steps[_AXIS(AXIS)]; \
  341. if (_COUNTER(AXIS) > 0) { _APPLY_STEP(AXIS)(!_INVERT_STEP_PIN(AXIS),0); }
  342. STEP_ADD(X);
  343. STEP_ADD(Y);
  344. STEP_ADD(Z);
  345. #if DISABLED(ADVANCE) && DISABLED(LIN_ADVANCE)
  346. STEP_ADD(E);
  347. #endif
  348. #define STEP_IF_COUNTER(AXIS) \
  349. if (_COUNTER(AXIS) > 0) { \
  350. _COUNTER(AXIS) -= current_block->step_event_count; \
  351. count_position[_AXIS(AXIS)] += count_direction[_AXIS(AXIS)]; \
  352. _APPLY_STEP(AXIS)(_INVERT_STEP_PIN(AXIS),0); \
  353. }
  354. STEP_IF_COUNTER(X);
  355. STEP_IF_COUNTER(Y);
  356. STEP_IF_COUNTER(Z);
  357. #if DISABLED(ADVANCE) && DISABLED(LIN_ADVANCE)
  358. STEP_IF_COUNTER(E);
  359. #endif
  360. step_events_completed++;
  361. if (step_events_completed >= current_block->step_event_count) break;
  362. }
  363. #if ENABLED(LIN_ADVANCE)
  364. // If we have esteps to execute, fire the next ISR "now"
  365. if (e_steps[current_block->active_extruder]) OCR0A = TCNT0 + 2;
  366. #endif
  367. // Calculate new timer value
  368. unsigned short timer, step_rate;
  369. if (step_events_completed <= (unsigned long)current_block->accelerate_until) {
  370. MultiU24X32toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
  371. acc_step_rate += current_block->initial_rate;
  372. // upper limit
  373. NOMORE(acc_step_rate, current_block->nominal_rate);
  374. // step_rate to timer interval
  375. timer = calc_timer(acc_step_rate);
  376. OCR1A = timer;
  377. acceleration_time += timer;
  378. #if ENABLED(LIN_ADVANCE)
  379. if (current_block->use_advance_lead)
  380. current_estep_rate[current_block->active_extruder] = ((unsigned long)acc_step_rate * current_block->e_speed_multiplier8) >> 8;
  381. #elif ENABLED(ADVANCE)
  382. advance += advance_rate * step_loops;
  383. //NOLESS(advance, current_block->advance);
  384. // Do E steps + advance steps
  385. e_steps[current_block->active_extruder] += ((advance >> 8) - old_advance);
  386. old_advance = advance >> 8;
  387. #endif // ADVANCE or LIN_ADVANCE
  388. #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE)
  389. eISR_Rate = (timer >> 2) * step_loops / abs(e_steps[current_block->active_extruder]);
  390. #endif
  391. }
  392. else if (step_events_completed > (unsigned long)current_block->decelerate_after) {
  393. MultiU24X32toH16(step_rate, deceleration_time, current_block->acceleration_rate);
  394. if (step_rate <= acc_step_rate) { // Still decelerating?
  395. step_rate = acc_step_rate - step_rate;
  396. NOLESS(step_rate, current_block->final_rate);
  397. }
  398. else
  399. step_rate = current_block->final_rate;
  400. // step_rate to timer interval
  401. timer = calc_timer(step_rate);
  402. OCR1A = timer;
  403. deceleration_time += timer;
  404. #if ENABLED(LIN_ADVANCE)
  405. if (current_block->use_advance_lead)
  406. current_estep_rate[current_block->active_extruder] = ((unsigned long)step_rate * current_block->e_speed_multiplier8) >> 8;
  407. #elif ENABLED(ADVANCE)
  408. advance -= advance_rate * step_loops;
  409. NOLESS(advance, final_advance);
  410. // Do E steps + advance steps
  411. uint32_t advance_whole = advance >> 8;
  412. e_steps[current_block->active_extruder] += advance_whole - old_advance;
  413. old_advance = advance_whole;
  414. #endif // ADVANCE or LIN_ADVANCE
  415. #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE)
  416. eISR_Rate = (timer >> 2) * step_loops / abs(e_steps[current_block->active_extruder]);
  417. #endif
  418. }
  419. else {
  420. #if ENABLED(LIN_ADVANCE)
  421. if (current_block->use_advance_lead)
  422. current_estep_rate[current_block->active_extruder] = final_estep_rate;
  423. eISR_Rate = (OCR1A_nominal >> 2) * step_loops_nominal / abs(e_steps[current_block->active_extruder]);
  424. #endif
  425. OCR1A = OCR1A_nominal;
  426. // ensure we're running at the correct step rate, even if we just came off an acceleration
  427. step_loops = step_loops_nominal;
  428. }
  429. OCR1A = (OCR1A < (TCNT1 + 16)) ? (TCNT1 + 16) : OCR1A;
  430. // If current block is finished, reset pointer
  431. if (step_events_completed >= current_block->step_event_count) {
  432. current_block = NULL;
  433. planner.discard_current_block();
  434. }
  435. }
  436. }
  437. #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE)
  438. // Timer interrupt for E. e_steps is set in the main routine;
  439. // Timer 0 is shared with millies
  440. ISR(TIMER0_COMPA_vect) { Stepper::advance_isr(); }
  441. void Stepper::advance_isr() {
  442. old_OCR0A += eISR_Rate;
  443. OCR0A = old_OCR0A;
  444. #define STEP_E_ONCE(INDEX) \
  445. if (e_steps[INDEX] != 0) { \
  446. E## INDEX ##_STEP_WRITE(INVERT_E_STEP_PIN); \
  447. if (e_steps[INDEX] < 0) { \
  448. E## INDEX ##_DIR_WRITE(INVERT_E## INDEX ##_DIR); \
  449. e_steps[INDEX]++; \
  450. } \
  451. else if (e_steps[INDEX] > 0) { \
  452. E## INDEX ##_DIR_WRITE(!INVERT_E## INDEX ##_DIR); \
  453. e_steps[INDEX]--; \
  454. } \
  455. E## INDEX ##_STEP_WRITE(!INVERT_E_STEP_PIN); \
  456. }
  457. // Step all E steppers that have steps
  458. for (uint8_t i = 0; i < step_loops; i++) {
  459. STEP_E_ONCE(0);
  460. #if EXTRUDERS > 1
  461. STEP_E_ONCE(1);
  462. #if EXTRUDERS > 2
  463. STEP_E_ONCE(2);
  464. #if EXTRUDERS > 3
  465. STEP_E_ONCE(3);
  466. #endif
  467. #endif
  468. #endif
  469. }
  470. }
  471. #endif // ADVANCE or LIN_ADVANCE
  472. void Stepper::init() {
  473. digipot_init(); //Initialize Digipot Motor Current
  474. microstep_init(); //Initialize Microstepping Pins
  475. // initialise TMC Steppers
  476. #if ENABLED(HAVE_TMCDRIVER)
  477. tmc_init();
  478. #endif
  479. // initialise L6470 Steppers
  480. #if ENABLED(HAVE_L6470DRIVER)
  481. L6470_init();
  482. #endif
  483. // Initialize Dir Pins
  484. #if HAS_X_DIR
  485. X_DIR_INIT;
  486. #endif
  487. #if HAS_X2_DIR
  488. X2_DIR_INIT;
  489. #endif
  490. #if HAS_Y_DIR
  491. Y_DIR_INIT;
  492. #if ENABLED(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_DIR
  493. Y2_DIR_INIT;
  494. #endif
  495. #endif
  496. #if HAS_Z_DIR
  497. Z_DIR_INIT;
  498. #if ENABLED(Z_DUAL_STEPPER_DRIVERS) && HAS_Z2_DIR
  499. Z2_DIR_INIT;
  500. #endif
  501. #endif
  502. #if HAS_E0_DIR
  503. E0_DIR_INIT;
  504. #endif
  505. #if HAS_E1_DIR
  506. E1_DIR_INIT;
  507. #endif
  508. #if HAS_E2_DIR
  509. E2_DIR_INIT;
  510. #endif
  511. #if HAS_E3_DIR
  512. E3_DIR_INIT;
  513. #endif
  514. //Initialize Enable Pins - steppers default to disabled.
  515. #if HAS_X_ENABLE
  516. X_ENABLE_INIT;
  517. if (!X_ENABLE_ON) X_ENABLE_WRITE(HIGH);
  518. #if ENABLED(DUAL_X_CARRIAGE) && HAS_X2_ENABLE
  519. X2_ENABLE_INIT;
  520. if (!X_ENABLE_ON) X2_ENABLE_WRITE(HIGH);
  521. #endif
  522. #endif
  523. #if HAS_Y_ENABLE
  524. Y_ENABLE_INIT;
  525. if (!Y_ENABLE_ON) Y_ENABLE_WRITE(HIGH);
  526. #if ENABLED(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_ENABLE
  527. Y2_ENABLE_INIT;
  528. if (!Y_ENABLE_ON) Y2_ENABLE_WRITE(HIGH);
  529. #endif
  530. #endif
  531. #if HAS_Z_ENABLE
  532. Z_ENABLE_INIT;
  533. if (!Z_ENABLE_ON) Z_ENABLE_WRITE(HIGH);
  534. #if ENABLED(Z_DUAL_STEPPER_DRIVERS) && HAS_Z2_ENABLE
  535. Z2_ENABLE_INIT;
  536. if (!Z_ENABLE_ON) Z2_ENABLE_WRITE(HIGH);
  537. #endif
  538. #endif
  539. #if HAS_E0_ENABLE
  540. E0_ENABLE_INIT;
  541. if (!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH);
  542. #endif
  543. #if HAS_E1_ENABLE
  544. E1_ENABLE_INIT;
  545. if (!E_ENABLE_ON) E1_ENABLE_WRITE(HIGH);
  546. #endif
  547. #if HAS_E2_ENABLE
  548. E2_ENABLE_INIT;
  549. if (!E_ENABLE_ON) E2_ENABLE_WRITE(HIGH);
  550. #endif
  551. #if HAS_E3_ENABLE
  552. E3_ENABLE_INIT;
  553. if (!E_ENABLE_ON) E3_ENABLE_WRITE(HIGH);
  554. #endif
  555. //
  556. // Init endstops and pullups here
  557. //
  558. endstops.init();
  559. #define _STEP_INIT(AXIS) AXIS ##_STEP_INIT
  560. #define _WRITE_STEP(AXIS, HIGHLOW) AXIS ##_STEP_WRITE(HIGHLOW)
  561. #define _DISABLE(axis) disable_## axis()
  562. #define AXIS_INIT(axis, AXIS, PIN) \
  563. _STEP_INIT(AXIS); \
  564. _WRITE_STEP(AXIS, _INVERT_STEP_PIN(PIN)); \
  565. _DISABLE(axis)
  566. #define E_AXIS_INIT(NUM) AXIS_INIT(e## NUM, E## NUM, E)
  567. // Initialize Step Pins
  568. #if HAS_X_STEP
  569. AXIS_INIT(x, X, X);
  570. #if ENABLED(DUAL_X_CARRIAGE) && HAS_X2_STEP
  571. AXIS_INIT(x, X2, X);
  572. #endif
  573. #endif
  574. #if HAS_Y_STEP
  575. #if ENABLED(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_STEP
  576. Y2_STEP_INIT;
  577. Y2_STEP_WRITE(INVERT_Y_STEP_PIN);
  578. #endif
  579. AXIS_INIT(y, Y, Y);
  580. #endif
  581. #if HAS_Z_STEP
  582. #if ENABLED(Z_DUAL_STEPPER_DRIVERS) && HAS_Z2_STEP
  583. Z2_STEP_INIT;
  584. Z2_STEP_WRITE(INVERT_Z_STEP_PIN);
  585. #endif
  586. AXIS_INIT(z, Z, Z);
  587. #endif
  588. #if HAS_E0_STEP
  589. E_AXIS_INIT(0);
  590. #endif
  591. #if HAS_E1_STEP
  592. E_AXIS_INIT(1);
  593. #endif
  594. #if HAS_E2_STEP
  595. E_AXIS_INIT(2);
  596. #endif
  597. #if HAS_E3_STEP
  598. E_AXIS_INIT(3);
  599. #endif
  600. // waveform generation = 0100 = CTC
  601. CBI(TCCR1B, WGM13);
  602. SBI(TCCR1B, WGM12);
  603. CBI(TCCR1A, WGM11);
  604. CBI(TCCR1A, WGM10);
  605. // output mode = 00 (disconnected)
  606. TCCR1A &= ~(3 << COM1A0);
  607. TCCR1A &= ~(3 << COM1B0);
  608. // Set the timer pre-scaler
  609. // Generally we use a divider of 8, resulting in a 2MHz timer
  610. // frequency on a 16MHz MCU. If you are going to change this, be
  611. // sure to regenerate speed_lookuptable.h with
  612. // create_speed_lookuptable.py
  613. TCCR1B = (TCCR1B & ~(0x07 << CS10)) | (2 << CS10);
  614. OCR1A = 0x4000;
  615. TCNT1 = 0;
  616. ENABLE_STEPPER_DRIVER_INTERRUPT();
  617. #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE)
  618. #if ENABLED(LIN_ADVANCE)
  619. for (int i = 0; i < EXTRUDERS; i++) {
  620. e_steps[i] = 0;
  621. current_adv_steps[i] = 0;
  622. }
  623. #elif ENABLED(ADVANCE)
  624. for (uint8_t i = 0; i < EXTRUDERS; i++) e_steps[i] = 0;
  625. #endif
  626. #if defined(TCCR0A) && defined(WGM01)
  627. CBI(TCCR0A, WGM01);
  628. CBI(TCCR0A, WGM00);
  629. #endif
  630. SBI(TIMSK0, OCIE0A);
  631. #endif // ADVANCE or LIN_ADVANCE
  632. endstops.enable(true); // Start with endstops active. After homing they can be disabled
  633. sei();
  634. set_directions(); // Init directions to last_direction_bits = 0
  635. }
  636. /**
  637. * Block until all buffered steps are executed
  638. */
  639. void Stepper::synchronize() { while (planner.blocks_queued()) idle(); }
  640. /**
  641. * Set the stepper positions directly in steps
  642. *
  643. * The input is based on the typical per-axis XYZ steps.
  644. * For CORE machines XYZ needs to be translated to ABC.
  645. *
  646. * This allows get_axis_position_mm to correctly
  647. * derive the current XYZ position later on.
  648. */
  649. void Stepper::set_position(const long& x, const long& y, const long& z, const long& e) {
  650. CRITICAL_SECTION_START;
  651. #if ENABLED(COREXY)
  652. // corexy positioning
  653. // these equations follow the form of the dA and dB equations on http://www.corexy.com/theory.html
  654. count_position[A_AXIS] = x + y;
  655. count_position[B_AXIS] = x - y;
  656. count_position[Z_AXIS] = z;
  657. #elif ENABLED(COREXZ)
  658. // corexz planning
  659. count_position[A_AXIS] = x + z;
  660. count_position[Y_AXIS] = y;
  661. count_position[C_AXIS] = x - z;
  662. #elif ENABLED(COREYZ)
  663. // coreyz planning
  664. count_position[X_AXIS] = x;
  665. count_position[B_AXIS] = y + z;
  666. count_position[C_AXIS] = y - z;
  667. #else
  668. // default non-h-bot planning
  669. count_position[X_AXIS] = x;
  670. count_position[Y_AXIS] = y;
  671. count_position[Z_AXIS] = z;
  672. #endif
  673. count_position[E_AXIS] = e;
  674. CRITICAL_SECTION_END;
  675. }
  676. void Stepper::set_e_position(const long& e) {
  677. CRITICAL_SECTION_START;
  678. count_position[E_AXIS] = e;
  679. CRITICAL_SECTION_END;
  680. }
  681. /**
  682. * Get a stepper's position in steps.
  683. */
  684. long Stepper::position(AxisEnum axis) {
  685. CRITICAL_SECTION_START;
  686. long count_pos = count_position[axis];
  687. CRITICAL_SECTION_END;
  688. return count_pos;
  689. }
  690. /**
  691. * Get an axis position according to stepper position(s)
  692. * For CORE machines apply translation from ABC to XYZ.
  693. */
  694. float Stepper::get_axis_position_mm(AxisEnum axis) {
  695. float axis_steps;
  696. #if ENABLED(COREXY) || ENABLED(COREXZ) || ENABLED(COREYZ)
  697. // Requesting one of the "core" axes?
  698. if (axis == CORE_AXIS_1 || axis == CORE_AXIS_2) {
  699. CRITICAL_SECTION_START;
  700. long pos1 = count_position[CORE_AXIS_1],
  701. pos2 = count_position[CORE_AXIS_2];
  702. CRITICAL_SECTION_END;
  703. // ((a1+a2)+(a1-a2))/2 -> (a1+a2+a1-a2)/2 -> (a1+a1)/2 -> a1
  704. // ((a1+a2)-(a1-a2))/2 -> (a1+a2-a1+a2)/2 -> (a2+a2)/2 -> a2
  705. axis_steps = (pos1 + ((axis == CORE_AXIS_1) ? pos2 : -pos2)) / 2.0f;
  706. }
  707. else
  708. axis_steps = position(axis);
  709. #else
  710. axis_steps = position(axis);
  711. #endif
  712. return axis_steps / planner.axis_steps_per_mm[axis];
  713. }
  714. void Stepper::finish_and_disable() {
  715. synchronize();
  716. disable_all_steppers();
  717. }
  718. void Stepper::quick_stop() {
  719. cleaning_buffer_counter = 5000;
  720. DISABLE_STEPPER_DRIVER_INTERRUPT();
  721. while (planner.blocks_queued()) planner.discard_current_block();
  722. current_block = NULL;
  723. ENABLE_STEPPER_DRIVER_INTERRUPT();
  724. }
  725. void Stepper::endstop_triggered(AxisEnum axis) {
  726. #if ENABLED(COREXY) || ENABLED(COREXZ) || ENABLED(COREYZ)
  727. float axis_pos = count_position[axis];
  728. if (axis == CORE_AXIS_1)
  729. axis_pos = (axis_pos + count_position[CORE_AXIS_2]) / 2;
  730. else if (axis == CORE_AXIS_2)
  731. axis_pos = (count_position[CORE_AXIS_1] - axis_pos) / 2;
  732. endstops_trigsteps[axis] = axis_pos;
  733. #else // !COREXY && !COREXZ && !COREYZ
  734. endstops_trigsteps[axis] = count_position[axis];
  735. #endif // !COREXY && !COREXZ && !COREYZ
  736. kill_current_block();
  737. }
  738. void Stepper::report_positions() {
  739. CRITICAL_SECTION_START;
  740. long xpos = count_position[X_AXIS],
  741. ypos = count_position[Y_AXIS],
  742. zpos = count_position[Z_AXIS];
  743. CRITICAL_SECTION_END;
  744. #if ENABLED(COREXY) || ENABLED(COREXZ)
  745. SERIAL_PROTOCOLPGM(MSG_COUNT_A);
  746. #else
  747. SERIAL_PROTOCOLPGM(MSG_COUNT_X);
  748. #endif
  749. SERIAL_PROTOCOL(xpos);
  750. #if ENABLED(COREXY) || ENABLED(COREYZ)
  751. SERIAL_PROTOCOLPGM(" B:");
  752. #else
  753. SERIAL_PROTOCOLPGM(" Y:");
  754. #endif
  755. SERIAL_PROTOCOL(ypos);
  756. #if ENABLED(COREXZ) || ENABLED(COREYZ)
  757. SERIAL_PROTOCOLPGM(" C:");
  758. #else
  759. SERIAL_PROTOCOLPGM(" Z:");
  760. #endif
  761. SERIAL_PROTOCOL(zpos);
  762. SERIAL_EOL;
  763. }
  764. #if ENABLED(BABYSTEPPING)
  765. // MUST ONLY BE CALLED BY AN ISR,
  766. // No other ISR should ever interrupt this!
  767. void Stepper::babystep(const uint8_t axis, const bool direction) {
  768. #define _ENABLE(axis) enable_## axis()
  769. #define _READ_DIR(AXIS) AXIS ##_DIR_READ
  770. #define _INVERT_DIR(AXIS) INVERT_## AXIS ##_DIR
  771. #define _APPLY_DIR(AXIS, INVERT) AXIS ##_APPLY_DIR(INVERT, true)
  772. #define BABYSTEP_AXIS(axis, AXIS, INVERT) { \
  773. _ENABLE(axis); \
  774. uint8_t old_pin = _READ_DIR(AXIS); \
  775. _APPLY_DIR(AXIS, _INVERT_DIR(AXIS)^direction^INVERT); \
  776. _APPLY_STEP(AXIS)(!_INVERT_STEP_PIN(AXIS), true); \
  777. delayMicroseconds(2); \
  778. _APPLY_STEP(AXIS)(_INVERT_STEP_PIN(AXIS), true); \
  779. _APPLY_DIR(AXIS, old_pin); \
  780. }
  781. switch (axis) {
  782. case X_AXIS:
  783. BABYSTEP_AXIS(x, X, false);
  784. break;
  785. case Y_AXIS:
  786. BABYSTEP_AXIS(y, Y, false);
  787. break;
  788. case Z_AXIS: {
  789. #if DISABLED(DELTA)
  790. BABYSTEP_AXIS(z, Z, BABYSTEP_INVERT_Z);
  791. #else // DELTA
  792. bool z_direction = direction ^ BABYSTEP_INVERT_Z;
  793. enable_x();
  794. enable_y();
  795. enable_z();
  796. uint8_t old_x_dir_pin = X_DIR_READ,
  797. old_y_dir_pin = Y_DIR_READ,
  798. old_z_dir_pin = Z_DIR_READ;
  799. //setup new step
  800. X_DIR_WRITE(INVERT_X_DIR ^ z_direction);
  801. Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction);
  802. Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction);
  803. //perform step
  804. X_STEP_WRITE(!INVERT_X_STEP_PIN);
  805. Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
  806. Z_STEP_WRITE(!INVERT_Z_STEP_PIN);
  807. delayMicroseconds(2);
  808. X_STEP_WRITE(INVERT_X_STEP_PIN);
  809. Y_STEP_WRITE(INVERT_Y_STEP_PIN);
  810. Z_STEP_WRITE(INVERT_Z_STEP_PIN);
  811. //get old pin state back.
  812. X_DIR_WRITE(old_x_dir_pin);
  813. Y_DIR_WRITE(old_y_dir_pin);
  814. Z_DIR_WRITE(old_z_dir_pin);
  815. #endif
  816. } break;
  817. default: break;
  818. }
  819. }
  820. #endif //BABYSTEPPING
  821. /**
  822. * Software-controlled Stepper Motor Current
  823. */
  824. #if HAS_DIGIPOTSS
  825. // From Arduino DigitalPotControl example
  826. void Stepper::digitalPotWrite(int address, int value) {
  827. digitalWrite(DIGIPOTSS_PIN, LOW); // take the SS pin low to select the chip
  828. SPI.transfer(address); // send in the address and value via SPI:
  829. SPI.transfer(value);
  830. digitalWrite(DIGIPOTSS_PIN, HIGH); // take the SS pin high to de-select the chip:
  831. //delay(10);
  832. }
  833. #endif //HAS_DIGIPOTSS
  834. void Stepper::digipot_init() {
  835. #if HAS_DIGIPOTSS
  836. const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT;
  837. SPI.begin();
  838. pinMode(DIGIPOTSS_PIN, OUTPUT);
  839. for (uint8_t i = 0; i < COUNT(digipot_motor_current); i++) {
  840. //digitalPotWrite(digipot_ch[i], digipot_motor_current[i]);
  841. digipot_current(i, digipot_motor_current[i]);
  842. }
  843. #endif
  844. #if HAS_MOTOR_CURRENT_PWM
  845. #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
  846. pinMode(MOTOR_CURRENT_PWM_XY_PIN, OUTPUT);
  847. digipot_current(0, motor_current_setting[0]);
  848. #endif
  849. #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
  850. pinMode(MOTOR_CURRENT_PWM_Z_PIN, OUTPUT);
  851. digipot_current(1, motor_current_setting[1]);
  852. #endif
  853. #if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
  854. pinMode(MOTOR_CURRENT_PWM_E_PIN, OUTPUT);
  855. digipot_current(2, motor_current_setting[2]);
  856. #endif
  857. //Set timer5 to 31khz so the PWM of the motor power is as constant as possible. (removes a buzzing noise)
  858. TCCR5B = (TCCR5B & ~(_BV(CS50) | _BV(CS51) | _BV(CS52))) | _BV(CS50);
  859. #endif
  860. }
  861. void Stepper::digipot_current(uint8_t driver, int current) {
  862. #if HAS_DIGIPOTSS
  863. const uint8_t digipot_ch[] = DIGIPOT_CHANNELS;
  864. digitalPotWrite(digipot_ch[driver], current);
  865. #elif HAS_MOTOR_CURRENT_PWM
  866. #define _WRITE_CURRENT_PWM(P) analogWrite(P, 255L * current / (MOTOR_CURRENT_PWM_RANGE))
  867. switch (driver) {
  868. #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
  869. case 0: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_XY_PIN); break;
  870. #endif
  871. #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
  872. case 1: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_Z_PIN); break;
  873. #endif
  874. #if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
  875. case 2: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_E_PIN); break;
  876. #endif
  877. }
  878. #else
  879. UNUSED(driver);
  880. UNUSED(current);
  881. #endif
  882. }
  883. void Stepper::microstep_init() {
  884. #if HAS_MICROSTEPS_E1
  885. pinMode(E1_MS1_PIN, OUTPUT);
  886. pinMode(E1_MS2_PIN, OUTPUT);
  887. #endif
  888. #if HAS_MICROSTEPS
  889. pinMode(X_MS1_PIN, OUTPUT);
  890. pinMode(X_MS2_PIN, OUTPUT);
  891. pinMode(Y_MS1_PIN, OUTPUT);
  892. pinMode(Y_MS2_PIN, OUTPUT);
  893. pinMode(Z_MS1_PIN, OUTPUT);
  894. pinMode(Z_MS2_PIN, OUTPUT);
  895. pinMode(E0_MS1_PIN, OUTPUT);
  896. pinMode(E0_MS2_PIN, OUTPUT);
  897. const uint8_t microstep_modes[] = MICROSTEP_MODES;
  898. for (uint16_t i = 0; i < COUNT(microstep_modes); i++)
  899. microstep_mode(i, microstep_modes[i]);
  900. #endif
  901. }
  902. /**
  903. * Software-controlled Microstepping
  904. */
  905. void Stepper::microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2) {
  906. if (ms1 >= 0) switch (driver) {
  907. case 0: digitalWrite(X_MS1_PIN, ms1); break;
  908. case 1: digitalWrite(Y_MS1_PIN, ms1); break;
  909. case 2: digitalWrite(Z_MS1_PIN, ms1); break;
  910. case 3: digitalWrite(E0_MS1_PIN, ms1); break;
  911. #if HAS_MICROSTEPS_E1
  912. case 4: digitalWrite(E1_MS1_PIN, ms1); break;
  913. #endif
  914. }
  915. if (ms2 >= 0) switch (driver) {
  916. case 0: digitalWrite(X_MS2_PIN, ms2); break;
  917. case 1: digitalWrite(Y_MS2_PIN, ms2); break;
  918. case 2: digitalWrite(Z_MS2_PIN, ms2); break;
  919. case 3: digitalWrite(E0_MS2_PIN, ms2); break;
  920. #if PIN_EXISTS(E1_MS2)
  921. case 4: digitalWrite(E1_MS2_PIN, ms2); break;
  922. #endif
  923. }
  924. }
  925. void Stepper::microstep_mode(uint8_t driver, uint8_t stepping_mode) {
  926. switch (stepping_mode) {
  927. case 1: microstep_ms(driver, MICROSTEP1); break;
  928. case 2: microstep_ms(driver, MICROSTEP2); break;
  929. case 4: microstep_ms(driver, MICROSTEP4); break;
  930. case 8: microstep_ms(driver, MICROSTEP8); break;
  931. case 16: microstep_ms(driver, MICROSTEP16); break;
  932. }
  933. }
  934. void Stepper::microstep_readings() {
  935. SERIAL_PROTOCOLLNPGM("MS1,MS2 Pins");
  936. SERIAL_PROTOCOLPGM("X: ");
  937. SERIAL_PROTOCOL(digitalRead(X_MS1_PIN));
  938. SERIAL_PROTOCOLLN(digitalRead(X_MS2_PIN));
  939. SERIAL_PROTOCOLPGM("Y: ");
  940. SERIAL_PROTOCOL(digitalRead(Y_MS1_PIN));
  941. SERIAL_PROTOCOLLN(digitalRead(Y_MS2_PIN));
  942. SERIAL_PROTOCOLPGM("Z: ");
  943. SERIAL_PROTOCOL(digitalRead(Z_MS1_PIN));
  944. SERIAL_PROTOCOLLN(digitalRead(Z_MS2_PIN));
  945. SERIAL_PROTOCOLPGM("E0: ");
  946. SERIAL_PROTOCOL(digitalRead(E0_MS1_PIN));
  947. SERIAL_PROTOCOLLN(digitalRead(E0_MS2_PIN));
  948. #if HAS_MICROSTEPS_E1
  949. SERIAL_PROTOCOLPGM("E1: ");
  950. SERIAL_PROTOCOL(digitalRead(E1_MS1_PIN));
  951. SERIAL_PROTOCOLLN(digitalRead(E1_MS2_PIN));
  952. #endif
  953. }
  954. #if ENABLED(LIN_ADVANCE)
  955. void Stepper::advance_M905(const float &k) {
  956. if (k >= 0) extruder_advance_k = k;
  957. SERIAL_ECHO_START;
  958. SERIAL_ECHOPAIR("Advance factor: ", extruder_advance_k);
  959. SERIAL_EOL;
  960. }
  961. #endif // LIN_ADVANCE