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.h 13KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397
  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.h - stepper motor driver: executes motion plans of planner.c using the stepper motors
  24. * Derived from Grbl
  25. *
  26. * Copyright (c) 2009-2011 Simen Svale Skogsrud
  27. *
  28. * Grbl is free software: you can redistribute it and/or modify
  29. * it under the terms of the GNU General Public License as published by
  30. * the Free Software Foundation, either version 3 of the License, or
  31. * (at your option) any later version.
  32. *
  33. * Grbl is distributed in the hope that it will be useful,
  34. * but WITHOUT ANY WARRANTY; without even the implied warranty of
  35. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  36. * GNU General Public License for more details.
  37. *
  38. * You should have received a copy of the GNU General Public License
  39. * along with Grbl. If not, see <http://www.gnu.org/licenses/>.
  40. */
  41. #ifndef STEPPER_H
  42. #define STEPPER_H
  43. #include "planner.h"
  44. #include "speed_lookuptable.h"
  45. #include "stepper_indirection.h"
  46. #include "language.h"
  47. #include "types.h"
  48. class Stepper;
  49. extern Stepper stepper;
  50. // intRes = intIn1 * intIn2 >> 16
  51. // uses:
  52. // r26 to store 0
  53. // r27 to store the byte 1 of the 24 bit result
  54. #define MultiU16X8toH16(intRes, charIn1, intIn2) \
  55. asm volatile ( \
  56. "clr r26 \n\t" \
  57. "mul %A1, %B2 \n\t" \
  58. "movw %A0, r0 \n\t" \
  59. "mul %A1, %A2 \n\t" \
  60. "add %A0, r1 \n\t" \
  61. "adc %B0, r26 \n\t" \
  62. "lsr r0 \n\t" \
  63. "adc %A0, r26 \n\t" \
  64. "adc %B0, r26 \n\t" \
  65. "clr r1 \n\t" \
  66. : \
  67. "=&r" (intRes) \
  68. : \
  69. "d" (charIn1), \
  70. "d" (intIn2) \
  71. : \
  72. "r26" \
  73. )
  74. class Stepper {
  75. public:
  76. static block_t* current_block; // A pointer to the block currently being traced
  77. #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
  78. static bool abort_on_endstop_hit;
  79. #endif
  80. #if ENABLED(Z_DUAL_ENDSTOPS)
  81. static bool performing_homing;
  82. #endif
  83. #if HAS_MOTOR_CURRENT_PWM
  84. #ifndef PWM_MOTOR_CURRENT
  85. #define PWM_MOTOR_CURRENT DEFAULT_PWM_MOTOR_CURRENT
  86. #endif
  87. static uint32_t motor_current_setting[3];
  88. #endif
  89. private:
  90. static uint8_t last_direction_bits; // The next stepping-bits to be output
  91. static uint16_t cleaning_buffer_counter;
  92. #if ENABLED(Z_DUAL_ENDSTOPS)
  93. static bool locked_z_motor, locked_z2_motor;
  94. #endif
  95. // Counter variables for the Bresenham line tracer
  96. static long counter_X, counter_Y, counter_Z, counter_E;
  97. static volatile uint32_t step_events_completed; // The number of step events executed in the current block
  98. #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE)
  99. static uint16_t nextMainISR, nextAdvanceISR, eISR_Rate;
  100. #define _NEXT_ISR(T) nextMainISR = T
  101. #if ENABLED(LIN_ADVANCE)
  102. static volatile int e_steps[E_STEPPERS];
  103. static int final_estep_rate;
  104. static int current_estep_rate[E_STEPPERS]; // Actual extruder speed [steps/s]
  105. static int current_adv_steps[E_STEPPERS]; // The amount of current added esteps due to advance.
  106. // i.e., the current amount of pressure applied
  107. // to the spring (=filament).
  108. #else
  109. static long e_steps[E_STEPPERS];
  110. static long advance_rate, advance, final_advance;
  111. static long old_advance;
  112. #endif
  113. #else
  114. #define _NEXT_ISR(T) OCR1A = T
  115. #endif // ADVANCE or LIN_ADVANCE
  116. static long acceleration_time, deceleration_time;
  117. //unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
  118. static unsigned short acc_step_rate; // needed for deceleration start point
  119. static uint8_t step_loops, step_loops_nominal;
  120. static unsigned short OCR1A_nominal;
  121. static volatile long endstops_trigsteps[XYZ];
  122. static volatile long endstops_stepsTotal, endstops_stepsDone;
  123. //
  124. // Positions of stepper motors, in step units
  125. //
  126. static volatile long count_position[NUM_AXIS];
  127. //
  128. // Current direction of stepper motors (+1 or -1)
  129. //
  130. static volatile signed char count_direction[NUM_AXIS];
  131. //
  132. // Mixing extruder mix counters
  133. //
  134. #if ENABLED(MIXING_EXTRUDER)
  135. static long counter_m[MIXING_STEPPERS];
  136. #define MIXING_STEPPERS_LOOP(VAR) \
  137. for (uint8_t VAR = 0; VAR < MIXING_STEPPERS; VAR++) \
  138. if (current_block->mix_event_count[VAR])
  139. #endif
  140. public:
  141. //
  142. // Constructor / initializer
  143. //
  144. Stepper() { };
  145. //
  146. // Initialize stepper hardware
  147. //
  148. static void init();
  149. //
  150. // Interrupt Service Routines
  151. //
  152. static void isr();
  153. #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE)
  154. static void advance_isr();
  155. static void advance_isr_scheduler();
  156. #endif
  157. //
  158. // Block until all buffered steps are executed
  159. //
  160. static void synchronize();
  161. //
  162. // Set the current position in steps
  163. //
  164. static void set_position(const long &a, const long &b, const long &c, const long &e);
  165. static void set_position(const AxisEnum &a, const long &v);
  166. static void set_e_position(const long &e);
  167. //
  168. // Set direction bits for all steppers
  169. //
  170. static void set_directions();
  171. //
  172. // Get the position of a stepper, in steps
  173. //
  174. static long position(AxisEnum axis);
  175. //
  176. // Report the positions of the steppers, in steps
  177. //
  178. static void report_positions();
  179. //
  180. // Get the position (mm) of an axis based on stepper position(s)
  181. //
  182. static float get_axis_position_mm(AxisEnum axis);
  183. //
  184. // SCARA AB axes are in degrees, not mm
  185. //
  186. #if IS_SCARA
  187. static FORCE_INLINE float get_axis_position_degrees(AxisEnum axis) { return get_axis_position_mm(axis); }
  188. #endif
  189. //
  190. // The stepper subsystem goes to sleep when it runs out of things to execute. Call this
  191. // to notify the subsystem that it is time to go to work.
  192. //
  193. static void wake_up();
  194. //
  195. // Wait for moves to finish and disable all steppers
  196. //
  197. static void finish_and_disable();
  198. //
  199. // Quickly stop all steppers and clear the blocks queue
  200. //
  201. static void quick_stop();
  202. //
  203. // The direction of a single motor
  204. //
  205. static FORCE_INLINE bool motor_direction(AxisEnum axis) { return TEST(last_direction_bits, axis); }
  206. #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM
  207. static void digitalPotWrite(const int16_t address, const int16_t value);
  208. static void digipot_current(const uint8_t driver, const int16_t current);
  209. #endif
  210. #if HAS_MICROSTEPS
  211. static void microstep_ms(const uint8_t driver, const int8_t ms1, const int8_t ms2);
  212. static void microstep_mode(const uint8_t driver, const uint8_t stepping);
  213. static void microstep_readings();
  214. #endif
  215. #if ENABLED(Z_DUAL_ENDSTOPS)
  216. static FORCE_INLINE void set_homing_flag(const bool state) { performing_homing = state; }
  217. static FORCE_INLINE void set_z_lock(const bool state) { locked_z_motor = state; }
  218. static FORCE_INLINE void set_z2_lock(const bool state) { locked_z2_motor = state; }
  219. #endif
  220. #if ENABLED(BABYSTEPPING)
  221. static void babystep(const AxisEnum axis, const bool direction); // perform a short step with a single stepper motor, outside of any convention
  222. #endif
  223. static inline void kill_current_block() {
  224. step_events_completed = current_block->step_event_count;
  225. }
  226. //
  227. // Handle a triggered endstop
  228. //
  229. static void endstop_triggered(AxisEnum axis);
  230. //
  231. // Triggered position of an axis in mm (not core-savvy)
  232. //
  233. static FORCE_INLINE float triggered_position_mm(AxisEnum axis) {
  234. return endstops_trigsteps[axis] * planner.steps_to_mm[axis];
  235. }
  236. #if HAS_MOTOR_CURRENT_PWM
  237. static void refresh_motor_power();
  238. #endif
  239. private:
  240. static FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) {
  241. unsigned short timer;
  242. NOMORE(step_rate, MAX_STEP_FREQUENCY);
  243. if (step_rate > 20000) { // If steprate > 20kHz >> step 4 times
  244. step_rate >>= 2;
  245. step_loops = 4;
  246. }
  247. else if (step_rate > 10000) { // If steprate > 10kHz >> step 2 times
  248. step_rate >>= 1;
  249. step_loops = 2;
  250. }
  251. else {
  252. step_loops = 1;
  253. }
  254. NOLESS(step_rate, F_CPU / 500000);
  255. step_rate -= F_CPU / 500000; // Correct for minimal speed
  256. if (step_rate >= (8 * 256)) { // higher step rate
  257. unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate >> 8)][0];
  258. unsigned char tmp_step_rate = (step_rate & 0x00FF);
  259. unsigned short gain = (unsigned short)pgm_read_word_near(table_address + 2);
  260. MultiU16X8toH16(timer, tmp_step_rate, gain);
  261. timer = (unsigned short)pgm_read_word_near(table_address) - timer;
  262. }
  263. else { // lower step rates
  264. unsigned short table_address = (unsigned short)&speed_lookuptable_slow[0][0];
  265. table_address += ((step_rate) >> 1) & 0xFFFC;
  266. timer = (unsigned short)pgm_read_word_near(table_address);
  267. timer -= (((unsigned short)pgm_read_word_near(table_address + 2) * (unsigned char)(step_rate & 0x0007)) >> 3);
  268. }
  269. if (timer < 100) { // (20kHz - this should never happen)
  270. timer = 100;
  271. MYSERIAL.print(MSG_STEPPER_TOO_HIGH);
  272. MYSERIAL.println(step_rate);
  273. }
  274. return timer;
  275. }
  276. // Initialize the trapezoid generator from the current block.
  277. // Called whenever a new block begins.
  278. static FORCE_INLINE void trapezoid_generator_reset() {
  279. static int8_t last_extruder = -1;
  280. if (current_block->direction_bits != last_direction_bits || current_block->active_extruder != last_extruder) {
  281. last_direction_bits = current_block->direction_bits;
  282. last_extruder = current_block->active_extruder;
  283. set_directions();
  284. }
  285. #if ENABLED(ADVANCE)
  286. advance = current_block->initial_advance;
  287. final_advance = current_block->final_advance;
  288. // Do E steps + advance steps
  289. #if ENABLED(MIXING_EXTRUDER)
  290. long advance_factor = (advance >> 8) - old_advance;
  291. // ...for mixing steppers proportionally
  292. MIXING_STEPPERS_LOOP(j)
  293. e_steps[j] += advance_factor * current_block->step_event_count / current_block->mix_event_count[j];
  294. #else
  295. // ...for the active extruder
  296. e_steps[TOOL_E_INDEX] += ((advance >> 8) - old_advance);
  297. #endif
  298. old_advance = advance >> 8;
  299. #endif
  300. deceleration_time = 0;
  301. // step_rate to timer interval
  302. OCR1A_nominal = calc_timer(current_block->nominal_rate);
  303. // make a note of the number of step loops required at nominal speed
  304. step_loops_nominal = step_loops;
  305. acc_step_rate = current_block->initial_rate;
  306. acceleration_time = calc_timer(acc_step_rate);
  307. _NEXT_ISR(acceleration_time);
  308. #if ENABLED(LIN_ADVANCE)
  309. if (current_block->use_advance_lead) {
  310. current_estep_rate[current_block->active_extruder] = ((unsigned long)acc_step_rate * current_block->abs_adv_steps_multiplier8) >> 17;
  311. final_estep_rate = (current_block->nominal_rate * current_block->abs_adv_steps_multiplier8) >> 17;
  312. }
  313. #endif
  314. // SERIAL_ECHO_START();
  315. // SERIAL_ECHOPGM("advance :");
  316. // SERIAL_ECHO(current_block->advance/256.0);
  317. // SERIAL_ECHOPGM("advance rate :");
  318. // SERIAL_ECHO(current_block->advance_rate/256.0);
  319. // SERIAL_ECHOPGM("initial advance :");
  320. // SERIAL_ECHO(current_block->initial_advance/256.0);
  321. // SERIAL_ECHOPGM("final advance :");
  322. // SERIAL_ECHOLN(current_block->final_advance/256.0);
  323. }
  324. #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM
  325. static void digipot_init();
  326. #endif
  327. #if HAS_MICROSTEPS
  328. static void microstep_init();
  329. #endif
  330. };
  331. #endif // STEPPER_H