No Description
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.

steppers.cpp 23KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756
  1. #include <Arduino.h>
  2. #include <AccelStepper.h>
  3. #include "config.h"
  4. #include "config_pins.h"
  5. #include "common.h"
  6. #include "lcd.h"
  7. #include "data.h"
  8. #include "states.h"
  9. #include "steppers.h"
  10. #define DEBUG_PRINT_STEPPER_HOME
  11. #define DISABLE_ENDSTOP_CHECKS_AT_RUNTIME
  12. static AccelStepper stepper_x(AccelStepper::DRIVER, X_STEP_PIN, X_DIR_PIN, 0, 0, false);
  13. static AccelStepper stepper_y(AccelStepper::DRIVER, Y_STEP_PIN, Y_DIR_PIN, 0, 0, false);
  14. static AccelStepper stepper_z(AccelStepper::DRIVER, Z_STEP_PIN, Z_DIR_PIN, 0, 0, false);
  15. static AccelStepper stepper_e(AccelStepper::DRIVER, E0_STEP_PIN, E0_DIR_PIN, 0, 0, false);
  16. // X Y Z
  17. #define HOME_PHASE_START 0
  18. #define HOME_PHASE_BACK 1
  19. #define HOME_PHASE_FINE 2
  20. // E
  21. #define HOME_PHASE_END 3
  22. enum stepper_states {
  23. step_disabled,
  24. step_not_homed,
  25. step_homing_x_fast,
  26. step_homing_x_back,
  27. step_homing_x_slow,
  28. step_homing_y_fast,
  29. step_homing_y_back,
  30. step_homing_y_slow,
  31. step_homing_z_fast,
  32. step_homing_z_back,
  33. step_homing_z_slow,
  34. step_homing_e_start,
  35. step_homing_e_left,
  36. step_homing_e_right,
  37. step_homing_e_end,
  38. step_homed
  39. };
  40. static volatile stepper_states state = step_disabled;
  41. static volatile unsigned long steppers_home_move_start_time = 0;
  42. static volatile bool x_finished = true;
  43. static volatile bool y_finished = true;
  44. static volatile bool z_finished = true;
  45. static volatile bool e_finished = true;
  46. void steppers_init(void) {
  47. pinMode(X_ENDSTOP_PIN, INPUT_PULLUP);
  48. pinMode(Y_ENDSTOP_PIN, INPUT_PULLUP);
  49. pinMode(Z_ENDSTOP_PIN, INPUT_PULLUP);
  50. pinMode(E_ENDSTOP_PIN, INPUT_PULLUP);
  51. pinMode(X_ENABLE_PIN, OUTPUT);
  52. pinMode(X_STEP_PIN, OUTPUT);
  53. pinMode(X_DIR_PIN, OUTPUT);
  54. pinMode(Y_ENABLE_PIN, OUTPUT);
  55. pinMode(Y_STEP_PIN, OUTPUT);
  56. pinMode(Y_DIR_PIN, OUTPUT);
  57. pinMode(Z_ENABLE_PIN, OUTPUT);
  58. pinMode(Z_STEP_PIN, OUTPUT);
  59. pinMode(Z_DIR_PIN, OUTPUT);
  60. pinMode(E0_ENABLE_PIN, OUTPUT);
  61. pinMode(E0_STEP_PIN, OUTPUT);
  62. pinMode(E0_DIR_PIN, OUTPUT);
  63. // fan connected to D8 for electronics
  64. pinMode(FAN_PIN, OUTPUT);
  65. digitalWrite(FAN_PIN, LOW);
  66. stepper_x.setEnablePin(X_ENABLE_PIN);
  67. stepper_x.setPinsInverted(false, false, true);
  68. steppers_set_speed_x(data_options()->speed_x);
  69. steppers_set_accel_x(data_options()->accel_x);
  70. stepper_y.setEnablePin(Y_ENABLE_PIN);
  71. stepper_y.setPinsInverted(false, false, true);
  72. steppers_set_speed_y(data_options()->speed_y);
  73. steppers_set_accel_y(data_options()->accel_y);
  74. stepper_z.setEnablePin(Z_ENABLE_PIN);
  75. stepper_z.setPinsInverted(false, false, true);
  76. steppers_set_speed_z(data_options()->speed_z);
  77. steppers_set_accel_z(data_options()->accel_z);
  78. stepper_e.setEnablePin(E0_ENABLE_PIN);
  79. stepper_e.setPinsInverted(false, false, true);
  80. steppers_set_speed_e(data_options()->speed_e);
  81. steppers_set_accel_e(data_options()->accel_e);
  82. }
  83. static void steppers_initiate_home(int axis, int phase) {
  84. #ifdef DEBUG_PRINT_STEPPER_HOME
  85. Serial.print(F("steppers_initiate_home("));
  86. if (axis == X_AXIS) {
  87. Serial.print('X');
  88. } else if (axis == Y_AXIS) {
  89. Serial.print('Y');
  90. } else if (axis == Z_AXIS) {
  91. Serial.print('Z');
  92. } else if (axis == E_AXIS) {
  93. Serial.print('E');
  94. } else {
  95. Serial.print(axis);
  96. }
  97. Serial.print(F(", "));
  98. Serial.print(phase);
  99. Serial.println(F(")"));
  100. #endif // DEBUG_PRINT_STEPPER_HOME
  101. CLEAR_STORE_INTERRUPTS();
  102. steppers_home_move_start_time = millis();
  103. if (axis == X_AXIS) {
  104. if (phase == HOME_PHASE_START) {
  105. if (steppers_home_switch(axis)) {
  106. #if (X_MIN_PIN == -1)
  107. stepper_x.setCurrentPosition(X_AXIS_MAX * XY_STEPS_PER_MM * X_AXIS_MOVEMENT_DIR);
  108. #else
  109. stepper_x.setCurrentPosition(X_AXIS_MIN * XY_STEPS_PER_MM * X_AXIS_MOVEMENT_DIR);
  110. #endif
  111. steppers_initiate_home(Y_AXIS, HOME_PHASE_START);
  112. } else {
  113. state = step_homing_x_fast;
  114. stepper_x.setSpeed(X_HOMING_DIR * X_AXIS_MOVEMENT_DIR * XY_FAST_HOME_SPEED * XY_STEPS_PER_MM);
  115. }
  116. } else if (phase == HOME_PHASE_BACK) {
  117. state = step_homing_x_back;
  118. stepper_x.setSpeed(-1.0 * X_HOMING_DIR * X_AXIS_MOVEMENT_DIR * XY_FAST_HOME_SPEED * XY_STEPS_PER_MM);
  119. } else if (phase == HOME_PHASE_FINE) {
  120. state = step_homing_x_slow;
  121. stepper_x.setSpeed(X_HOMING_DIR * X_AXIS_MOVEMENT_DIR * XY_SLOW_HOME_SPEED * XY_STEPS_PER_MM);
  122. }
  123. } else if (axis == Y_AXIS) {
  124. if (phase == HOME_PHASE_START) {
  125. if (steppers_home_switch(axis)) {
  126. #if (Y_MIN_PIN == -1)
  127. stepper_y.setCurrentPosition(Y_AXIS_MAX * XY_STEPS_PER_MM * Y_AXIS_MOVEMENT_DIR);
  128. #else
  129. stepper_y.setCurrentPosition(Y_AXIS_MIN * XY_STEPS_PER_MM * Y_AXIS_MOVEMENT_DIR);
  130. #endif
  131. steppers_initiate_home(E_AXIS, HOME_PHASE_START);
  132. } else {
  133. state = step_homing_y_fast;
  134. stepper_y.setSpeed(Y_HOMING_DIR * Y_AXIS_MOVEMENT_DIR * XY_FAST_HOME_SPEED * XY_STEPS_PER_MM);
  135. }
  136. } else if (phase == HOME_PHASE_BACK) {
  137. state = step_homing_y_back;
  138. stepper_y.setSpeed(-1.0 * Y_HOMING_DIR * Y_AXIS_MOVEMENT_DIR * XY_FAST_HOME_SPEED * XY_STEPS_PER_MM);
  139. } else if (phase == HOME_PHASE_FINE) {
  140. state = step_homing_y_slow;
  141. stepper_y.setSpeed(Y_HOMING_DIR * Y_AXIS_MOVEMENT_DIR * XY_SLOW_HOME_SPEED * XY_STEPS_PER_MM);
  142. }
  143. } else if (axis == Z_AXIS) {
  144. if (phase == HOME_PHASE_START) {
  145. state = step_homing_z_fast;
  146. stepper_z.setSpeed(Z_HOMING_DIR * Z_AXIS_MOVEMENT_DIR * Z_FAST_HOME_SPEED * Z_STEPS_PER_MM);
  147. } else if (phase == HOME_PHASE_BACK) {
  148. state = step_homing_z_back;
  149. stepper_z.setSpeed(-1.0 * Z_HOMING_DIR * Z_AXIS_MOVEMENT_DIR * Z_FAST_HOME_SPEED * Z_STEPS_PER_MM);
  150. } else if (phase == HOME_PHASE_FINE) {
  151. state = step_homing_z_slow;
  152. stepper_z.setSpeed(Z_HOMING_DIR * Z_AXIS_MOVEMENT_DIR * Z_SLOW_HOME_SPEED * Z_STEPS_PER_MM);
  153. }
  154. } else if (axis == E_AXIS) {
  155. if (phase == HOME_PHASE_START) {
  156. if (steppers_home_switch(axis)) {
  157. Serial.println(F("already hit, continue"));
  158. steppers_initiate_home(E_AXIS, HOME_PHASE_BACK);
  159. } else {
  160. Serial.println(F("moving towards endstop"));
  161. state = step_homing_e_start;
  162. stepper_e.setSpeed(-1.0 * E_HOMING_DIR * E_AXIS_MOVEMENT_DIR * E_FAST_HOME_SPEED * E_STEPS_PER_PERCENT);
  163. }
  164. } else if (phase == HOME_PHASE_BACK) {
  165. Serial.println(F("moving toward left end"));
  166. state = step_homing_e_left;
  167. stepper_e.setSpeed(E_HOMING_DIR * E_AXIS_MOVEMENT_DIR * E_SLOW_HOME_SPEED * E_STEPS_PER_PERCENT);
  168. } else if (phase == HOME_PHASE_FINE) {
  169. Serial.print(F("moving toward right end, at "));
  170. Serial.println(E_MM_TO_PERCENT(E_AXIS_MAX / 2) * E_STEPS_PER_PERCENT * E_AXIS_MOVEMENT_DIR * E_HOMING_DIR);
  171. state = step_homing_e_right;
  172. stepper_e.setMaxSpeed(E_SLOW_HOME_SPEED * E_STEPS_PER_PERCENT);
  173. stepper_e.moveTo(E_MM_TO_PERCENT(E_AXIS_MAX / 2) * E_STEPS_PER_PERCENT * E_AXIS_MOVEMENT_DIR * E_HOMING_DIR);
  174. } else if (phase == HOME_PHASE_END) {
  175. Serial.print(F("moving toward new zero, at "));
  176. Serial.println(stepper_e.currentPosition() / 2);
  177. state = step_homing_e_end;
  178. stepper_e.setMaxSpeed(E_FAST_HOME_SPEED * E_STEPS_PER_PERCENT);
  179. stepper_e.moveTo(stepper_e.currentPosition() / 2);
  180. }
  181. } else {
  182. Serial.println(F("home_init error: invalid axis"));
  183. }
  184. RESTORE_INTERRUPTS();
  185. }
  186. bool steppers_home_switch(int axis) {
  187. bool r = true;
  188. CLEAR_STORE_INTERRUPTS();
  189. if (axis == X_AXIS) {
  190. r = digitalRead(X_ENDSTOP_PIN) == LOW;
  191. } else if (axis == Y_AXIS) {
  192. r = digitalRead(Y_ENDSTOP_PIN) == LOW;
  193. } else if (axis == Z_AXIS) {
  194. r = digitalRead(Z_ENDSTOP_PIN) == LOW;
  195. } else if (axis == E_AXIS) {
  196. r = digitalRead(E_ENDSTOP_PIN) == LOW;
  197. } else {
  198. Serial.println(F("home_switch error: invalid axis"));
  199. }
  200. RESTORE_INTERRUPTS();
  201. return r;
  202. }
  203. bool stepper_reached_target(int axis) {
  204. if (axis == X_AXIS) {
  205. return x_finished;
  206. } else if (axis == Y_AXIS) {
  207. return y_finished;
  208. } else if (axis == Z_AXIS) {
  209. return z_finished;
  210. } else if (axis == E_AXIS) {
  211. return e_finished;
  212. } else {
  213. Serial.println(F("stepper_reached_target error: invalid axis"));
  214. return false;
  215. }
  216. }
  217. float steppers_current_pos(int axis) {
  218. float r = 0.0;
  219. CLEAR_STORE_INTERRUPTS();
  220. if (axis == X_AXIS) {
  221. float v = stepper_x.currentPosition();
  222. r = v / XY_STEPS_PER_MM / X_AXIS_MOVEMENT_DIR;
  223. } else if (axis == Y_AXIS) {
  224. float v = stepper_y.currentPosition();
  225. r = v / XY_STEPS_PER_MM / Y_AXIS_MOVEMENT_DIR;
  226. } else if (axis == Z_AXIS) {
  227. float v = stepper_z.currentPosition();
  228. r = v / Z_STEPS_PER_MM / Z_AXIS_MOVEMENT_DIR;
  229. } else if (axis == E_AXIS) {
  230. float v = stepper_e.currentPosition();
  231. r = E_PERCENT_TO_MM(v / E_STEPS_PER_PERCENT / E_AXIS_MOVEMENT_DIR);
  232. } else {
  233. Serial.println(F("steppers_pos error: invalid axis"));
  234. }
  235. RESTORE_INTERRUPTS();
  236. return r;
  237. }
  238. // TODO split into separate run funcs for running and homing
  239. // TODO only enable timer1 when either homing or moving
  240. // TODO disable timer1 when no longer homing/moving
  241. // TODO (when timer is disabled, still call in normal loop?)
  242. void steppers_run(void) {
  243. if ((state == step_homed) || (state == step_not_homed)) {
  244. #ifndef DISABLE_ENDSTOP_CHECKS_AT_RUNTIME
  245. for (int i = 0; i < AXIS_COUNT; i++) {
  246. #if 0
  247. Serial.print(i);
  248. Serial.print(": ");
  249. Serial.println(steppers_current_pos(i));
  250. #endif
  251. if (steppers_home_switch(i)) {
  252. float compare = 0.0, epsilon = 0.0;
  253. if (i == X_AXIS) {
  254. epsilon = X_AXIS_EPSILON;
  255. #if (X_HOMING_DIR == 1)
  256. compare = X_AXIS_MAX;
  257. #else
  258. compare = X_AXIS_MIN;
  259. #endif
  260. } else if (i == Y_AXIS) {
  261. epsilon = Y_AXIS_EPSILON;
  262. #if (Y_HOMING_DIR == 1)
  263. compare = Y_AXIS_MAX;
  264. #else
  265. compare = Y_AXIS_MIN;
  266. #endif
  267. } else if (i == Z_AXIS) {
  268. epsilon = Z_AXIS_EPSILON;
  269. #if (Z_HOMING_DIR == 1)
  270. compare = Z_AXIS_MAX;
  271. #else
  272. compare = Z_AXIS_MIN;
  273. #endif
  274. } else if (i == E_AXIS) {
  275. epsilon = E_AXIS_EPSILON;
  276. // TODO compare to 0 and 200%!
  277. }
  278. if (fabs(steppers_current_pos(i) - compare) > epsilon) {
  279. #if 0
  280. Serial.print(F("Endstop hit at "));
  281. Serial.println(steppers_current_pos(i));
  282. #endif
  283. steppers_kill();
  284. if (i == X_AXIS) {
  285. sm_error.setText("Enstop hit on X axis");
  286. } else if (i == Y_AXIS) {
  287. sm_error.setText("Enstop hit on Y axis");
  288. } else if (i == Z_AXIS) {
  289. sm_error.setText("Enstop hit on Z axis");
  290. } else if (i == E_AXIS) {
  291. sm_error.setText("Enstop hit on E axis");
  292. } else {
  293. sm_error.setText("Enstop hit on unknown axis");
  294. }
  295. states_go_to(&sm_error);
  296. }
  297. }
  298. }
  299. #endif // DISABLE_ENDSTOP_CHECKS_AT_RUNTIME
  300. x_finished = !stepper_x.run();
  301. y_finished = !stepper_y.run();
  302. z_finished = !stepper_z.run();
  303. e_finished = !stepper_e.run();
  304. } else if (state == step_homing_x_fast) {
  305. if (steppers_home_switch(X_AXIS)) {
  306. steppers_initiate_home(X_AXIS, HOME_PHASE_BACK);
  307. } else {
  308. stepper_x.runSpeed();
  309. }
  310. } else if (state == step_homing_x_back) {
  311. unsigned long end_time = steppers_home_move_start_time + XY_HOME_BACK_OFF_TIME;
  312. if ((!steppers_home_switch(X_AXIS)) && (millis() >= end_time)) {
  313. steppers_initiate_home(X_AXIS, HOME_PHASE_FINE);
  314. } else {
  315. stepper_x.runSpeed();
  316. }
  317. } else if (state == step_homing_x_slow) {
  318. if (steppers_home_switch(X_AXIS)) {
  319. stepper_x.setSpeed(0);
  320. #if (X_MIN_PIN == -1)
  321. stepper_x.setCurrentPosition(X_AXIS_MAX * XY_STEPS_PER_MM * X_AXIS_MOVEMENT_DIR);
  322. #else
  323. stepper_x.setCurrentPosition(X_AXIS_MIN * XY_STEPS_PER_MM * X_AXIS_MOVEMENT_DIR);
  324. #endif
  325. steppers_initiate_home(Y_AXIS, HOME_PHASE_START);
  326. } else {
  327. stepper_x.runSpeed();
  328. }
  329. } else if (state == step_homing_y_fast) {
  330. if (steppers_home_switch(Y_AXIS)) {
  331. steppers_initiate_home(Y_AXIS, HOME_PHASE_BACK);
  332. } else {
  333. stepper_y.runSpeed();
  334. }
  335. } else if (state == step_homing_y_back) {
  336. unsigned long end_time = steppers_home_move_start_time + XY_HOME_BACK_OFF_TIME;
  337. if ((!steppers_home_switch(Y_AXIS)) && (millis() >= end_time)) {
  338. steppers_initiate_home(Y_AXIS, HOME_PHASE_FINE);
  339. } else {
  340. stepper_y.runSpeed();
  341. }
  342. } else if (state == step_homing_y_slow) {
  343. if (steppers_home_switch(Y_AXIS)) {
  344. stepper_y.setSpeed(0);
  345. #if (Y_MIN_PIN == -1)
  346. stepper_y.setCurrentPosition(Y_AXIS_MAX * XY_STEPS_PER_MM * Y_AXIS_MOVEMENT_DIR);
  347. #else
  348. stepper_y.setCurrentPosition(Y_AXIS_MIN * XY_STEPS_PER_MM * Y_AXIS_MOVEMENT_DIR);
  349. #endif
  350. steppers_initiate_home(E_AXIS, HOME_PHASE_START);
  351. } else {
  352. stepper_y.runSpeed();
  353. }
  354. } else if (state == step_homing_z_fast) {
  355. if (steppers_home_switch(Z_AXIS)) {
  356. steppers_initiate_home(Z_AXIS, HOME_PHASE_BACK);
  357. } else {
  358. stepper_z.runSpeed();
  359. }
  360. } else if (state == step_homing_z_back) {
  361. unsigned long end_time = steppers_home_move_start_time + Z_HOME_BACK_OFF_TIME;
  362. if ((!steppers_home_switch(Z_AXIS)) && (millis() >= end_time)) {
  363. steppers_initiate_home(Z_AXIS, HOME_PHASE_FINE);
  364. } else {
  365. stepper_z.runSpeed();
  366. }
  367. } else if (state == step_homing_z_slow) {
  368. if (steppers_home_switch(Z_AXIS)) {
  369. stepper_z.setSpeed(0);
  370. #if (Z_MIN_PIN == -1)
  371. stepper_z.setCurrentPosition(Z_AXIS_MAX * Z_STEPS_PER_MM * Z_AXIS_MOVEMENT_DIR);
  372. #else
  373. stepper_z.setCurrentPosition(Z_AXIS_MIN * Z_STEPS_PER_MM * Z_AXIS_MOVEMENT_DIR);
  374. #endif
  375. steppers_initiate_home(X_AXIS, HOME_PHASE_START);
  376. } else {
  377. stepper_z.runSpeed();
  378. }
  379. } else if (state == step_homing_e_start) {
  380. if (steppers_home_switch(E_AXIS)) {
  381. steppers_initiate_home(E_AXIS, HOME_PHASE_BACK);
  382. } else {
  383. stepper_e.runSpeed();
  384. }
  385. } else if (state == step_homing_e_left) {
  386. if (!steppers_home_switch(E_AXIS)) {
  387. stepper_e.setSpeed(0);
  388. stepper_e.setCurrentPosition(0);
  389. steppers_initiate_home(E_AXIS, HOME_PHASE_FINE);
  390. } else {
  391. stepper_e.runSpeed();
  392. }
  393. } else if (state == step_homing_e_right) {
  394. if ((!steppers_home_switch(E_AXIS)) && ((stepper_e.currentPosition() > 200) || (stepper_e.currentPosition() < -200))) {
  395. // TODO only if we've moved a bit (250 is center)
  396. steppers_initiate_home(E_AXIS, HOME_PHASE_END);
  397. } else {
  398. stepper_e.run();
  399. }
  400. } else if (state == step_homing_e_end) {
  401. if (!stepper_e.run()) {
  402. stepper_e.setMaxSpeed(data_options()->speed_e * E_STEPS_PER_PERCENT);
  403. stepper_e.setCurrentPosition(E_MM_TO_PERCENT(E_AXIS_MIN) * E_STEPS_PER_PERCENT * E_AXIS_MOVEMENT_DIR);
  404. state = step_homed;
  405. }
  406. }
  407. }
  408. bool steppers_homed(void) {
  409. CLEAR_STORE_INTERRUPTS();
  410. bool r = (state == step_homed);
  411. RESTORE_INTERRUPTS();
  412. return r;
  413. }
  414. char steppers_homing_axis(void) {
  415. CLEAR_STORE_INTERRUPTS();
  416. char r = ' ';
  417. if ((state == step_homing_x_fast) || (state == step_homing_x_back) || (state == step_homing_x_slow)) {
  418. r = 'X';
  419. } else if ((state == step_homing_y_fast) || (state == step_homing_y_back) || (state == step_homing_y_slow)) {
  420. r = 'Y';
  421. } else if ((state == step_homing_z_fast) || (state == step_homing_z_back) || (state == step_homing_z_slow)) {
  422. r = 'Z';
  423. } else if ((state == step_homing_e_start) || (state == step_homing_e_left) || (state == step_homing_e_right) || (state == step_homing_e_end)) {
  424. r = 'E';
  425. }
  426. RESTORE_INTERRUPTS();
  427. return r;
  428. }
  429. void steppers_start_homing(void) {
  430. CLEAR_STORE_INTERRUPTS();
  431. digitalWrite(FAN_PIN, HIGH);
  432. stepper_x.enableOutputs();
  433. stepper_y.enableOutputs();
  434. stepper_z.enableOutputs();
  435. stepper_e.enableOutputs();
  436. // TODO
  437. //steppers_initiate_home(Z_AXIS, HOME_PHASE_START);
  438. steppers_initiate_home(X_AXIS, HOME_PHASE_START);
  439. RESTORE_INTERRUPTS();
  440. }
  441. static int steppers_move_axis(AccelStepper &axis, long pos) {
  442. CLEAR_STORE_INTERRUPTS();
  443. if (state == step_disabled) {
  444. Serial.println(F("Enabling stepper drivers"));
  445. digitalWrite(FAN_PIN, HIGH);
  446. stepper_x.enableOutputs();
  447. stepper_y.enableOutputs();
  448. stepper_z.enableOutputs();
  449. stepper_e.enableOutputs();
  450. state = step_not_homed;
  451. }
  452. if (!steppers_homed()) {
  453. Serial.println(F("WARNING: un-homed move!"));
  454. }
  455. axis.moveTo(pos);
  456. RESTORE_INTERRUPTS();
  457. return 0;
  458. }
  459. int steppers_move_x(float pos) {
  460. Serial.print(F("Moving X to "));
  461. Serial.print(pos);
  462. Serial.print(F(" mm ("));
  463. Serial.print(pos * XY_STEPS_PER_MM * X_AXIS_MOVEMENT_DIR);
  464. Serial.println(F(" steps)"));
  465. if (pos < X_AXIS_MIN) {
  466. Serial.println(F("Move below X_AXIS_MIN!"));
  467. return -1;
  468. }
  469. if (pos > X_AXIS_MAX) {
  470. Serial.println(F("Move above X_AXIS_MAX!"));
  471. return -1;
  472. }
  473. return steppers_move_axis(stepper_x, pos * XY_STEPS_PER_MM * X_AXIS_MOVEMENT_DIR);
  474. }
  475. int steppers_move_y(float pos) {
  476. Serial.print(F("Moving Y to "));
  477. Serial.print(pos);
  478. Serial.print(F(" mm ("));
  479. Serial.print(pos * XY_STEPS_PER_MM * Y_AXIS_MOVEMENT_DIR);
  480. Serial.println(F(" steps)"));
  481. if (pos < Y_AXIS_MIN) {
  482. Serial.println(F("Move below Y_AXIS_MIN!"));
  483. return -1;
  484. }
  485. if (pos > Y_AXIS_MAX) {
  486. Serial.println(F("Move above Y_AXIS_MAX!"));
  487. return -1;
  488. }
  489. return steppers_move_axis(stepper_y, pos * XY_STEPS_PER_MM * Y_AXIS_MOVEMENT_DIR);
  490. }
  491. int steppers_move_z(float pos) {
  492. Serial.print(F("Moving Z to "));
  493. Serial.print(pos);
  494. Serial.print(F(" mm ("));
  495. Serial.print(pos * Z_STEPS_PER_MM * Z_AXIS_MOVEMENT_DIR);
  496. Serial.println(F(" steps)"));
  497. if (pos < Z_AXIS_MIN) {
  498. Serial.println(F("Move below Z_AXIS_MIN!"));
  499. return -1;
  500. }
  501. if (pos > Z_AXIS_MAX) {
  502. Serial.println(F("Move above Z_AXIS_MAX!"));
  503. return -1;
  504. }
  505. return steppers_move_axis(stepper_z, pos * Z_STEPS_PER_MM * Z_AXIS_MOVEMENT_DIR);
  506. }
  507. int steppers_move_e(float pos) {
  508. Serial.print(F("Moving E to "));
  509. Serial.print(pos);
  510. Serial.print(F(" mm ("));
  511. Serial.print(E_MM_TO_PERCENT(pos));
  512. Serial.println(F("% = "));
  513. Serial.print(E_MM_TO_PERCENT(pos) * E_STEPS_PER_PERCENT * E_AXIS_MOVEMENT_DIR);
  514. Serial.println(F(" steps)"));
  515. if (pos < E_AXIS_MIN) {
  516. Serial.println(F("Move below E_AXIS_MIN!"));
  517. return -1;
  518. }
  519. if (pos > E_AXIS_MAX) {
  520. Serial.println(F("Move above E_AXIS_MAX!"));
  521. return -1;
  522. }
  523. return steppers_move_axis(stepper_e, E_MM_TO_PERCENT(pos) * E_STEPS_PER_PERCENT * E_AXIS_MOVEMENT_DIR);
  524. }
  525. float steppers_pos_x(void) {
  526. CLEAR_STORE_INTERRUPTS();
  527. float v = stepper_x.targetPosition();
  528. RESTORE_INTERRUPTS();
  529. return v / XY_STEPS_PER_MM / X_AXIS_MOVEMENT_DIR;
  530. }
  531. float steppers_pos_y(void) {
  532. CLEAR_STORE_INTERRUPTS();
  533. float v = stepper_y.targetPosition();
  534. RESTORE_INTERRUPTS();
  535. return v / XY_STEPS_PER_MM / Y_AXIS_MOVEMENT_DIR;
  536. }
  537. float steppers_pos_z(void) {
  538. CLEAR_STORE_INTERRUPTS();
  539. float v = stepper_z.targetPosition();
  540. RESTORE_INTERRUPTS();
  541. return v / Z_STEPS_PER_MM / Z_AXIS_MOVEMENT_DIR;
  542. }
  543. float steppers_pos_e(void) {
  544. CLEAR_STORE_INTERRUPTS();
  545. float v = stepper_e.targetPosition();
  546. RESTORE_INTERRUPTS();
  547. return E_PERCENT_TO_MM(v / E_STEPS_PER_PERCENT / E_AXIS_MOVEMENT_DIR);
  548. }
  549. void steppers_kill(void) {
  550. CLEAR_STORE_INTERRUPTS();
  551. stepper_x.setCurrentPosition(0);
  552. stepper_y.setCurrentPosition(0);
  553. stepper_z.setCurrentPosition(0);
  554. stepper_e.setCurrentPosition(0);
  555. stepper_x.disableOutputs();
  556. stepper_y.disableOutputs();
  557. stepper_z.disableOutputs();
  558. stepper_e.disableOutputs();
  559. digitalWrite(FAN_PIN, LOW);
  560. state = step_disabled;
  561. RESTORE_INTERRUPTS();
  562. }
  563. void steppers_set_speed_x(float speed) {
  564. if (speed < 0.0) {
  565. speed = 0.0;
  566. }
  567. if (speed > XY_MAX_SPEED) {
  568. speed = XY_MAX_SPEED;
  569. }
  570. CLEAR_STORE_INTERRUPTS();
  571. stepper_x.setMaxSpeed(speed * XY_STEPS_PER_MM);
  572. RESTORE_INTERRUPTS();
  573. }
  574. void steppers_set_speed_y(float speed) {
  575. if (speed < 0.0) {
  576. speed = 0.0;
  577. }
  578. if (speed > XY_MAX_SPEED) {
  579. speed = XY_MAX_SPEED;
  580. }
  581. CLEAR_STORE_INTERRUPTS();
  582. stepper_y.setMaxSpeed(speed * XY_STEPS_PER_MM);
  583. RESTORE_INTERRUPTS();
  584. }
  585. void steppers_set_speed_z(float speed) {
  586. if (speed < 0.0) {
  587. speed = 0.0;
  588. }
  589. if (speed > Z_MAX_SPEED) {
  590. speed = Z_MAX_SPEED;
  591. }
  592. CLEAR_STORE_INTERRUPTS();
  593. stepper_z.setMaxSpeed(speed * Z_STEPS_PER_MM);
  594. RESTORE_INTERRUPTS();
  595. }
  596. void steppers_set_speed_e(float speed) {
  597. if (speed < 0.0) {
  598. speed = 0.0;
  599. }
  600. if (speed > E_MAX_SPEED) {
  601. speed = E_MAX_SPEED;
  602. }
  603. CLEAR_STORE_INTERRUPTS();
  604. stepper_e.setMaxSpeed(speed * E_STEPS_PER_PERCENT);
  605. RESTORE_INTERRUPTS();
  606. }
  607. void steppers_set_accel_x(float accel) {
  608. if (accel < 0.0) {
  609. accel = 0.0;
  610. }
  611. if (accel > XY_MAX_ACCEL) {
  612. accel = XY_MAX_ACCEL;
  613. }
  614. CLEAR_STORE_INTERRUPTS();
  615. stepper_x.setAcceleration(accel * XY_STEPS_PER_MM);
  616. RESTORE_INTERRUPTS();
  617. }
  618. void steppers_set_accel_y(float accel) {
  619. if (accel < 0.0) {
  620. accel = 0.0;
  621. }
  622. if (accel > XY_MAX_ACCEL) {
  623. accel = XY_MAX_ACCEL;
  624. }
  625. CLEAR_STORE_INTERRUPTS();
  626. stepper_y.setAcceleration(accel * XY_STEPS_PER_MM);
  627. RESTORE_INTERRUPTS();
  628. }
  629. void steppers_set_accel_z(float accel) {
  630. if (accel < 0.0) {
  631. accel = 0.0;
  632. }
  633. if (accel > Z_MAX_ACCEL) {
  634. accel = Z_MAX_ACCEL;
  635. }
  636. CLEAR_STORE_INTERRUPTS();
  637. stepper_z.setAcceleration(accel * Z_STEPS_PER_MM);
  638. RESTORE_INTERRUPTS();
  639. }
  640. void steppers_set_accel_e(float accel) {
  641. if (accel < 0.0) {
  642. accel = 0.0;
  643. }
  644. if (accel > E_MAX_ACCEL) {
  645. accel = E_MAX_ACCEL;
  646. }
  647. CLEAR_STORE_INTERRUPTS();
  648. stepper_e.setAcceleration(accel * E_STEPS_PER_PERCENT);
  649. RESTORE_INTERRUPTS();
  650. }