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

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812181318141815181618171818181918201821182218231824182518261827182818291830183118321833183418351836183718381839184018411842184318441845184618471848184918501851185218531854185518561857185818591860186118621863186418651866186718681869187018711872187318741875187618771878187918801881188218831884188518861887188818891890189118921893189418951896189718981899190019011902190319041905190619071908190919101911191219131914191519161917191819191920192119221923192419251926192719281929193019311932193319341935193619371938193919401941194219431944194519461947194819491950195119521953195419551956195719581959196019611962196319641965196619671968196919701971197219731974197519761977197819791980198119821983198419851986198719881989199019911992199319941995199619971998199920002001200220032004200520062007200820092010201120122013201420152016201720182019202020212022202320242025202620272028202920302031203220332034203520362037203820392040204120422043204420452046204720482049205020512052205320542055205620572058205920602061206220632064206520662067206820692070207120722073207420752076207720782079208020812082208320842085208620872088208920902091209220932094209520962097209820992100210121022103210421052106210721082109211021112112211321142115211621172118211921202121212221232124212521262127212821292130213121322133213421352136213721382139214021412142214321442145214621472148214921502151215221532154215521562157215821592160216121622163216421652166216721682169217021712172217321742175217621772178217921802181218221832184218521862187218821892190219121922193219421952196219721982199220022012202220322042205220622072208220922102211221222132214221522162217221822192220222122222223222422252226222722282229223022312232223322342235223622372238223922402241224222432244224522462247224822492250225122522253225422552256225722582259226022612262226322642265226622672268226922702271227222732274227522762277227822792280228122822283228422852286228722882289229022912292229322942295229622972298229923002301230223032304230523062307230823092310231123122313231423152316231723182319232023212322232323242325232623272328232923302331233223332334233523362337233823392340234123422343234423452346234723482349235023512352235323542355235623572358235923602361236223632364236523662367236823692370237123722373237423752376237723782379238023812382238323842385238623872388238923902391239223932394239523962397239823992400240124022403240424052406240724082409241024112412241324142415241624172418241924202421242224232424242524262427242824292430243124322433243424352436243724382439244024412442244324442445244624472448244924502451245224532454245524562457245824592460246124622463246424652466246724682469247024712472247324742475247624772478247924802481248224832484248524862487248824892490249124922493249424952496249724982499250025012502250325042505250625072508250925102511251225132514251525162517251825192520252125222523252425252526252725282529253025312532253325342535253625372538253925402541254225432544254525462547254825492550255125522553255425552556255725582559256025612562256325642565256625672568256925702571257225732574257525762577257825792580258125822583258425852586258725882589259025912592259325942595259625972598259926002601260226032604260526062607260826092610261126122613261426152616261726182619262026212622262326242625262626272628262926302631263226332634263526362637263826392640264126422643264426452646264726482649265026512652265326542655265626572658265926602661266226632664266526662667266826692670267126722673267426752676267726782679268026812682268326842685268626872688268926902691269226932694269526962697269826992700270127022703270427052706270727082709271027112712271327142715271627172718271927202721272227232724272527262727272827292730273127322733273427352736273727382739274027412742274327442745274627472748274927502751275227532754275527562757275827592760276127622763276427652766276727682769277027712772277327742775277627772778277927802781278227832784278527862787278827892790279127922793279427952796279727982799280028012802280328042805280628072808280928102811281228132814281528162817281828192820282128222823282428252826282728282829283028312832283328342835283628372838283928402841284228432844284528462847284828492850285128522853285428552856285728582859286028612862286328642865286628672868286928702871287228732874287528762877287828792880288128822883288428852886288728882889289028912892289328942895289628972898289929002901290229032904290529062907290829092910291129122913291429152916291729182919292029212922292329242925292629272928292929302931293229332934293529362937293829392940294129422943294429452946294729482949295029512952295329542955295629572958295929602961296229632964296529662967296829692970297129722973297429752976297729782979298029812982298329842985298629872988298929902991299229932994299529962997299829993000300130023003300430053006300730083009301030113012301330143015301630173018301930203021302230233024302530263027302830293030303130323033303430353036303730383039304030413042304330443045304630473048304930503051305230533054305530563057305830593060306130623063306430653066306730683069307030713072307330743075307630773078307930803081308230833084308530863087308830893090309130923093309430953096309730983099310031013102310331043105310631073108310931103111311231133114311531163117311831193120312131223123312431253126312731283129313031313132313331343135313631373138313931403141314231433144314531463147314831493150315131523153315431553156315731583159316031613162316331643165316631673168316931703171317231733174317531763177317831793180318131823183318431853186318731883189319031913192319331943195319631973198319932003201320232033204320532063207320832093210321132123213321432153216321732183219322032213222322332243225322632273228
  1. /**
  2. * Marlin 3D Printer Firmware
  3. * Copyright (c) 2020 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. /**
  43. * Timer calculations informed by the 'RepRap cartesian firmware' by Zack Smith
  44. * and Philipp Tiefenbacher.
  45. */
  46. /**
  47. * __________________________
  48. * /| |\ _________________ ^
  49. * / | | \ /| |\ |
  50. * / | | \ / | | \ s
  51. * / | | | | | \ p
  52. * / | | | | | \ e
  53. * +-----+------------------------+---+--+---------------+----+ e
  54. * | BLOCK 1 | BLOCK 2 | d
  55. *
  56. * time ----->
  57. *
  58. * The trapezoid is the shape the speed curve over time. It starts at block->initial_rate, accelerates
  59. * first block->accelerate_until step_events_completed, then keeps going at constant speed until
  60. * step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset.
  61. * The slope of acceleration is calculated using v = u + at where t is the accumulated timer values of the steps so far.
  62. */
  63. /**
  64. * Marlin uses the Bresenham algorithm. For a detailed explanation of theory and
  65. * method see https://www.cs.helsinki.fi/group/goa/mallinnus/lines/bresenh.html
  66. */
  67. /**
  68. * Jerk controlled movements planner added Apr 2018 by Eduardo José Tagle.
  69. * Equations based on Synthethos TinyG2 sources, but the fixed-point
  70. * implementation is new, as we are running the ISR with a variable period.
  71. * Also implemented the Bézier velocity curve evaluation in ARM assembler,
  72. * to avoid impacting ISR speed.
  73. */
  74. #include "stepper.h"
  75. Stepper stepper; // Singleton
  76. #if HAS_MOTOR_CURRENT_PWM
  77. bool Stepper::initialized; // = false
  78. #endif
  79. #ifdef __AVR__
  80. #include "speed_lookuptable.h"
  81. #endif
  82. #include "endstops.h"
  83. #include "planner.h"
  84. #include "motion.h"
  85. #include "temperature.h"
  86. #include "../lcd/ultralcd.h"
  87. #include "../core/language.h"
  88. #include "../gcode/queue.h"
  89. #include "../sd/cardreader.h"
  90. #include "../MarlinCore.h"
  91. #include "../HAL/shared/Delay.h"
  92. #if ENABLED(INTEGRATED_BABYSTEPPING)
  93. #include "../feature/babystep.h"
  94. #endif
  95. #if MB(ALLIGATOR)
  96. #include "../feature/dac/dac_dac084s085.h"
  97. #endif
  98. #if HAS_DIGIPOTSS
  99. #include <SPI.h>
  100. #endif
  101. #if ENABLED(MIXING_EXTRUDER)
  102. #include "../feature/mixing.h"
  103. #endif
  104. #ifdef FILAMENT_RUNOUT_DISTANCE_MM
  105. #include "../feature/runout.h"
  106. #endif
  107. #if HAS_L64XX
  108. #include "../libs/L64XX/L64XX_Marlin.h"
  109. uint8_t L6470_buf[MAX_L64XX + 1]; // chip command sequence - element 0 not used
  110. bool L64XX_OK_to_power_up = false; // flag to keep L64xx steppers powered down after a reset or power up
  111. #endif
  112. #if ENABLED(POWER_LOSS_RECOVERY)
  113. #include "../feature/power_loss_recovery.h"
  114. #endif
  115. // public:
  116. #if HAS_EXTRA_ENDSTOPS || ENABLED(Z_STEPPER_AUTO_ALIGN)
  117. bool Stepper::separate_multi_axis = false;
  118. #endif
  119. #if HAS_MOTOR_CURRENT_PWM
  120. uint32_t Stepper::motor_current_setting[3]; // Initialized by settings.load()
  121. #endif
  122. // private:
  123. block_t* Stepper::current_block; // (= nullptr) A pointer to the block currently being traced
  124. uint8_t Stepper::last_direction_bits, // = 0
  125. Stepper::axis_did_move; // = 0
  126. bool Stepper::abort_current_block;
  127. #if DISABLED(MIXING_EXTRUDER) && EXTRUDERS > 1
  128. uint8_t Stepper::last_moved_extruder = 0xFF;
  129. #endif
  130. #if ENABLED(X_DUAL_ENDSTOPS)
  131. bool Stepper::locked_X_motor = false, Stepper::locked_X2_motor = false;
  132. #endif
  133. #if ENABLED(Y_DUAL_ENDSTOPS)
  134. bool Stepper::locked_Y_motor = false, Stepper::locked_Y2_motor = false;
  135. #endif
  136. #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
  137. bool Stepper::locked_Z_motor = false, Stepper::locked_Z2_motor = false
  138. #if NUM_Z_STEPPER_DRIVERS >= 3
  139. , Stepper::locked_Z3_motor = false
  140. #if NUM_Z_STEPPER_DRIVERS >= 4
  141. , Stepper::locked_Z4_motor = false
  142. #endif
  143. #endif
  144. ;
  145. #endif
  146. uint32_t Stepper::acceleration_time, Stepper::deceleration_time;
  147. uint8_t Stepper::steps_per_isr;
  148. #if DISABLED(ADAPTIVE_STEP_SMOOTHING)
  149. constexpr
  150. #endif
  151. uint8_t Stepper::oversampling_factor;
  152. xyze_long_t Stepper::delta_error{0};
  153. xyze_ulong_t Stepper::advance_dividend{0};
  154. uint32_t Stepper::advance_divisor = 0,
  155. Stepper::step_events_completed = 0, // The number of step events executed in the current block
  156. Stepper::accelerate_until, // The count at which to stop accelerating
  157. Stepper::decelerate_after, // The count at which to start decelerating
  158. Stepper::step_event_count; // The total event count for the current block
  159. #if EXTRUDERS > 1 || ENABLED(MIXING_EXTRUDER)
  160. uint8_t Stepper::stepper_extruder;
  161. #else
  162. constexpr uint8_t Stepper::stepper_extruder;
  163. #endif
  164. #if ENABLED(S_CURVE_ACCELERATION)
  165. int32_t __attribute__((used)) Stepper::bezier_A __asm__("bezier_A"); // A coefficient in Bézier speed curve with alias for assembler
  166. int32_t __attribute__((used)) Stepper::bezier_B __asm__("bezier_B"); // B coefficient in Bézier speed curve with alias for assembler
  167. int32_t __attribute__((used)) Stepper::bezier_C __asm__("bezier_C"); // C coefficient in Bézier speed curve with alias for assembler
  168. uint32_t __attribute__((used)) Stepper::bezier_F __asm__("bezier_F"); // F coefficient in Bézier speed curve with alias for assembler
  169. uint32_t __attribute__((used)) Stepper::bezier_AV __asm__("bezier_AV"); // AV coefficient in Bézier speed curve with alias for assembler
  170. #ifdef __AVR__
  171. bool __attribute__((used)) Stepper::A_negative __asm__("A_negative"); // If A coefficient was negative
  172. #endif
  173. bool Stepper::bezier_2nd_half; // =false If Bézier curve has been initialized or not
  174. #endif
  175. #if ENABLED(LIN_ADVANCE)
  176. uint32_t Stepper::nextAdvanceISR = LA_ADV_NEVER,
  177. Stepper::LA_isr_rate = LA_ADV_NEVER;
  178. uint16_t Stepper::LA_current_adv_steps = 0,
  179. Stepper::LA_final_adv_steps,
  180. Stepper::LA_max_adv_steps;
  181. int8_t Stepper::LA_steps = 0;
  182. bool Stepper::LA_use_advance_lead;
  183. #endif // LIN_ADVANCE
  184. #if ENABLED(INTEGRATED_BABYSTEPPING)
  185. uint32_t Stepper::nextBabystepISR = BABYSTEP_NEVER;
  186. #endif
  187. int32_t Stepper::ticks_nominal = -1;
  188. #if DISABLED(S_CURVE_ACCELERATION)
  189. uint32_t Stepper::acc_step_rate; // needed for deceleration start point
  190. #endif
  191. xyz_long_t Stepper::endstops_trigsteps;
  192. xyze_long_t Stepper::count_position{0};
  193. xyze_int8_t Stepper::count_direction{0};
  194. #define DUAL_ENDSTOP_APPLY_STEP(A,V) \
  195. if (separate_multi_axis) { \
  196. if (A##_HOME_DIR < 0) { \
  197. if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \
  198. if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
  199. } \
  200. else { \
  201. if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \
  202. if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
  203. } \
  204. } \
  205. else { \
  206. A##_STEP_WRITE(V); \
  207. A##2_STEP_WRITE(V); \
  208. }
  209. #define DUAL_SEPARATE_APPLY_STEP(A,V) \
  210. if (separate_multi_axis) { \
  211. if (!locked_##A##_motor) A##_STEP_WRITE(V); \
  212. if (!locked_##A##2_motor) A##2_STEP_WRITE(V); \
  213. } \
  214. else { \
  215. A##_STEP_WRITE(V); \
  216. A##2_STEP_WRITE(V); \
  217. }
  218. #define TRIPLE_ENDSTOP_APPLY_STEP(A,V) \
  219. if (separate_multi_axis) { \
  220. if (A##_HOME_DIR < 0) { \
  221. if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \
  222. if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
  223. if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \
  224. } \
  225. else { \
  226. if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \
  227. if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
  228. if (!(TEST(endstops.state(), A##3_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \
  229. } \
  230. } \
  231. else { \
  232. A##_STEP_WRITE(V); \
  233. A##2_STEP_WRITE(V); \
  234. A##3_STEP_WRITE(V); \
  235. }
  236. #define TRIPLE_SEPARATE_APPLY_STEP(A,V) \
  237. if (separate_multi_axis) { \
  238. if (!locked_##A##_motor) A##_STEP_WRITE(V); \
  239. if (!locked_##A##2_motor) A##2_STEP_WRITE(V); \
  240. if (!locked_##A##3_motor) A##3_STEP_WRITE(V); \
  241. } \
  242. else { \
  243. A##_STEP_WRITE(V); \
  244. A##2_STEP_WRITE(V); \
  245. A##3_STEP_WRITE(V); \
  246. }
  247. #define QUAD_ENDSTOP_APPLY_STEP(A,V) \
  248. if (separate_multi_axis) { \
  249. if (A##_HOME_DIR < 0) { \
  250. if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \
  251. if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
  252. if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \
  253. if (!(TEST(endstops.state(), A##4_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \
  254. } \
  255. else { \
  256. if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \
  257. if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
  258. if (!(TEST(endstops.state(), A##3_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \
  259. if (!(TEST(endstops.state(), A##4_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \
  260. } \
  261. } \
  262. else { \
  263. A##_STEP_WRITE(V); \
  264. A##2_STEP_WRITE(V); \
  265. A##3_STEP_WRITE(V); \
  266. A##4_STEP_WRITE(V); \
  267. }
  268. #define QUAD_SEPARATE_APPLY_STEP(A,V) \
  269. if (separate_multi_axis) { \
  270. if (!locked_##A##_motor) A##_STEP_WRITE(V); \
  271. if (!locked_##A##2_motor) A##2_STEP_WRITE(V); \
  272. if (!locked_##A##3_motor) A##3_STEP_WRITE(V); \
  273. if (!locked_##A##4_motor) A##4_STEP_WRITE(V); \
  274. } \
  275. else { \
  276. A##_STEP_WRITE(V); \
  277. A##2_STEP_WRITE(V); \
  278. A##3_STEP_WRITE(V); \
  279. A##4_STEP_WRITE(V); \
  280. }
  281. #if ENABLED(X_DUAL_STEPPER_DRIVERS)
  282. #define X_APPLY_DIR(v,Q) do{ X_DIR_WRITE(v); X2_DIR_WRITE((v) != INVERT_X2_VS_X_DIR); }while(0)
  283. #if ENABLED(X_DUAL_ENDSTOPS)
  284. #define X_APPLY_STEP(v,Q) DUAL_ENDSTOP_APPLY_STEP(X,v)
  285. #else
  286. #define X_APPLY_STEP(v,Q) do{ X_STEP_WRITE(v); X2_STEP_WRITE(v); }while(0)
  287. #endif
  288. #elif ENABLED(DUAL_X_CARRIAGE)
  289. #define X_APPLY_DIR(v,ALWAYS) do{ \
  290. if (extruder_duplication_enabled || ALWAYS) { X_DIR_WRITE(v); X2_DIR_WRITE(mirrored_duplication_mode ? !(v) : v); } \
  291. else if (movement_extruder()) X2_DIR_WRITE(v); else X_DIR_WRITE(v); \
  292. }while(0)
  293. #define X_APPLY_STEP(v,ALWAYS) do{ \
  294. if (extruder_duplication_enabled || ALWAYS) { X_STEP_WRITE(v); X2_STEP_WRITE(v); } \
  295. else if (movement_extruder()) X2_STEP_WRITE(v); else X_STEP_WRITE(v); \
  296. }while(0)
  297. #else
  298. #define X_APPLY_DIR(v,Q) X_DIR_WRITE(v)
  299. #define X_APPLY_STEP(v,Q) X_STEP_WRITE(v)
  300. #endif
  301. #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
  302. #define Y_APPLY_DIR(v,Q) do{ Y_DIR_WRITE(v); Y2_DIR_WRITE((v) != INVERT_Y2_VS_Y_DIR); }while(0)
  303. #if ENABLED(Y_DUAL_ENDSTOPS)
  304. #define Y_APPLY_STEP(v,Q) DUAL_ENDSTOP_APPLY_STEP(Y,v)
  305. #else
  306. #define Y_APPLY_STEP(v,Q) do{ Y_STEP_WRITE(v); Y2_STEP_WRITE(v); }while(0)
  307. #endif
  308. #else
  309. #define Y_APPLY_DIR(v,Q) Y_DIR_WRITE(v)
  310. #define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v)
  311. #endif
  312. #if NUM_Z_STEPPER_DRIVERS == 4
  313. #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); Z3_DIR_WRITE(v); Z4_DIR_WRITE(v); }while(0)
  314. #if ENABLED(Z_MULTI_ENDSTOPS)
  315. #define Z_APPLY_STEP(v,Q) QUAD_ENDSTOP_APPLY_STEP(Z,v)
  316. #elif ENABLED(Z_STEPPER_AUTO_ALIGN)
  317. #define Z_APPLY_STEP(v,Q) QUAD_SEPARATE_APPLY_STEP(Z,v)
  318. #else
  319. #define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); Z3_STEP_WRITE(v); Z4_STEP_WRITE(v); }while(0)
  320. #endif
  321. #elif NUM_Z_STEPPER_DRIVERS == 3
  322. #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); Z3_DIR_WRITE(v); }while(0)
  323. #if ENABLED(Z_MULTI_ENDSTOPS)
  324. #define Z_APPLY_STEP(v,Q) TRIPLE_ENDSTOP_APPLY_STEP(Z,v)
  325. #elif ENABLED(Z_STEPPER_AUTO_ALIGN)
  326. #define Z_APPLY_STEP(v,Q) TRIPLE_SEPARATE_APPLY_STEP(Z,v)
  327. #else
  328. #define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); Z3_STEP_WRITE(v); }while(0)
  329. #endif
  330. #elif NUM_Z_STEPPER_DRIVERS == 2
  331. #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); }while(0)
  332. #if ENABLED(Z_MULTI_ENDSTOPS)
  333. #define Z_APPLY_STEP(v,Q) DUAL_ENDSTOP_APPLY_STEP(Z,v)
  334. #elif ENABLED(Z_STEPPER_AUTO_ALIGN)
  335. #define Z_APPLY_STEP(v,Q) DUAL_SEPARATE_APPLY_STEP(Z,v)
  336. #else
  337. #define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); }while(0)
  338. #endif
  339. #else
  340. #define Z_APPLY_DIR(v,Q) Z_DIR_WRITE(v)
  341. #define Z_APPLY_STEP(v,Q) Z_STEP_WRITE(v)
  342. #endif
  343. #if DISABLED(MIXING_EXTRUDER)
  344. #define E_APPLY_STEP(v,Q) E_STEP_WRITE(stepper_extruder, v)
  345. #endif
  346. #define CYCLES_TO_NS(CYC) (1000UL * (CYC) / ((F_CPU) / 1000000))
  347. constexpr uint32_t NS_PER_PULSE_TIMER_TICK = 1000000000UL / (STEPPER_TIMER_RATE);
  348. // Round up when converting from ns to timer ticks
  349. constexpr uint32_t NS_TO_PULSE_TIMER_TICKS(uint32_t NS) { return (NS + (NS_PER_PULSE_TIMER_TICK) / 2) / (NS_PER_PULSE_TIMER_TICK); }
  350. #define TIMER_SETUP_NS (CYCLES_TO_NS(TIMER_READ_ADD_AND_STORE_CYCLES))
  351. #define PULSE_HIGH_TICK_COUNT hal_timer_t(NS_TO_PULSE_TIMER_TICKS(_MIN_PULSE_HIGH_NS - _MIN(_MIN_PULSE_HIGH_NS, TIMER_SETUP_NS)))
  352. #define PULSE_LOW_TICK_COUNT hal_timer_t(NS_TO_PULSE_TIMER_TICKS(_MIN_PULSE_LOW_NS - _MIN(_MIN_PULSE_LOW_NS, TIMER_SETUP_NS)))
  353. #define USING_TIMED_PULSE() hal_timer_t start_pulse_count = 0
  354. #define START_TIMED_PULSE(DIR) (start_pulse_count = HAL_timer_get_count(PULSE_TIMER_NUM))
  355. #define AWAIT_TIMED_PULSE(DIR) while (PULSE_##DIR##_TICK_COUNT > HAL_timer_get_count(PULSE_TIMER_NUM) - start_pulse_count) { }
  356. #define START_HIGH_PULSE() START_TIMED_PULSE(HIGH)
  357. #define AWAIT_HIGH_PULSE() AWAIT_TIMED_PULSE(HIGH)
  358. #define START_LOW_PULSE() START_TIMED_PULSE(LOW)
  359. #define AWAIT_LOW_PULSE() AWAIT_TIMED_PULSE(LOW)
  360. #if MINIMUM_STEPPER_PRE_DIR_DELAY > 0
  361. #define DIR_WAIT_BEFORE() DELAY_NS(MINIMUM_STEPPER_PRE_DIR_DELAY)
  362. #else
  363. #define DIR_WAIT_BEFORE()
  364. #endif
  365. #if MINIMUM_STEPPER_POST_DIR_DELAY > 0
  366. #define DIR_WAIT_AFTER() DELAY_NS(MINIMUM_STEPPER_POST_DIR_DELAY)
  367. #else
  368. #define DIR_WAIT_AFTER()
  369. #endif
  370. /**
  371. * Set the stepper direction of each axis
  372. *
  373. * COREXY: X_AXIS=A_AXIS and Y_AXIS=B_AXIS
  374. * COREXZ: X_AXIS=A_AXIS and Z_AXIS=C_AXIS
  375. * COREYZ: Y_AXIS=B_AXIS and Z_AXIS=C_AXIS
  376. */
  377. void Stepper::set_directions() {
  378. DIR_WAIT_BEFORE();
  379. #define SET_STEP_DIR(A) \
  380. if (motor_direction(_AXIS(A))) { \
  381. A##_APPLY_DIR(INVERT_##A##_DIR, false); \
  382. count_direction[_AXIS(A)] = -1; \
  383. } \
  384. else { \
  385. A##_APPLY_DIR(!INVERT_##A##_DIR, false); \
  386. count_direction[_AXIS(A)] = 1; \
  387. }
  388. #if HAS_X_DIR
  389. SET_STEP_DIR(X); // A
  390. #endif
  391. #if HAS_Y_DIR
  392. SET_STEP_DIR(Y); // B
  393. #endif
  394. #if HAS_Z_DIR
  395. SET_STEP_DIR(Z); // C
  396. #endif
  397. #if DISABLED(LIN_ADVANCE)
  398. #if ENABLED(MIXING_EXTRUDER)
  399. // Because this is valid for the whole block we don't know
  400. // what e-steppers will step. Likely all. Set all.
  401. if (motor_direction(E_AXIS)) {
  402. MIXER_STEPPER_LOOP(j) REV_E_DIR(j);
  403. count_direction.e = -1;
  404. }
  405. else {
  406. MIXER_STEPPER_LOOP(j) NORM_E_DIR(j);
  407. count_direction.e = 1;
  408. }
  409. #else
  410. if (motor_direction(E_AXIS)) {
  411. REV_E_DIR(stepper_extruder);
  412. count_direction.e = -1;
  413. }
  414. else {
  415. NORM_E_DIR(stepper_extruder);
  416. count_direction.e = 1;
  417. }
  418. #endif
  419. #endif // !LIN_ADVANCE
  420. #if HAS_L64XX
  421. if (L64XX_OK_to_power_up) { // OK to send the direction commands (which powers up the L64XX steppers)
  422. if (L64xxManager.spi_active) {
  423. L64xxManager.spi_abort = true; // Interrupted SPI transfer needs to shut down gracefully
  424. for (uint8_t j = 1; j <= L64XX::chain[0]; j++)
  425. L6470_buf[j] = dSPIN_NOP; // Fill buffer with NOOPs
  426. L64xxManager.transfer(L6470_buf, L64XX::chain[0]); // Send enough NOOPs to complete any command
  427. L64xxManager.transfer(L6470_buf, L64XX::chain[0]);
  428. L64xxManager.transfer(L6470_buf, L64XX::chain[0]);
  429. }
  430. // L64xxManager.dir_commands[] is an array that holds direction command for each stepper
  431. // Scan command array, copy matches into L64xxManager.transfer
  432. for (uint8_t j = 1; j <= L64XX::chain[0]; j++)
  433. L6470_buf[j] = L64xxManager.dir_commands[L64XX::chain[j]];
  434. L64xxManager.transfer(L6470_buf, L64XX::chain[0]); // send the command stream to the drivers
  435. }
  436. #endif
  437. DIR_WAIT_AFTER();
  438. }
  439. #if ENABLED(S_CURVE_ACCELERATION)
  440. /**
  441. * This uses a quintic (fifth-degree) Bézier polynomial for the velocity curve, giving
  442. * a "linear pop" velocity curve; with pop being the sixth derivative of position:
  443. * velocity - 1st, acceleration - 2nd, jerk - 3rd, snap - 4th, crackle - 5th, pop - 6th
  444. *
  445. * The Bézier curve takes the form:
  446. *
  447. * V(t) = P_0 * B_0(t) + P_1 * B_1(t) + P_2 * B_2(t) + P_3 * B_3(t) + P_4 * B_4(t) + P_5 * B_5(t)
  448. *
  449. * Where 0 <= t <= 1, and V(t) is the velocity. P_0 through P_5 are the control points, and B_0(t)
  450. * through B_5(t) are the Bernstein basis as follows:
  451. *
  452. * B_0(t) = (1-t)^5 = -t^5 + 5t^4 - 10t^3 + 10t^2 - 5t + 1
  453. * B_1(t) = 5(1-t)^4 * t = 5t^5 - 20t^4 + 30t^3 - 20t^2 + 5t
  454. * B_2(t) = 10(1-t)^3 * t^2 = -10t^5 + 30t^4 - 30t^3 + 10t^2
  455. * B_3(t) = 10(1-t)^2 * t^3 = 10t^5 - 20t^4 + 10t^3
  456. * B_4(t) = 5(1-t) * t^4 = -5t^5 + 5t^4
  457. * B_5(t) = t^5 = t^5
  458. * ^ ^ ^ ^ ^ ^
  459. * | | | | | |
  460. * A B C D E F
  461. *
  462. * Unfortunately, we cannot use forward-differencing to calculate each position through
  463. * the curve, as Marlin uses variable timer periods. So, we require a formula of the form:
  464. *
  465. * V_f(t) = A*t^5 + B*t^4 + C*t^3 + D*t^2 + E*t + F
  466. *
  467. * Looking at the above B_0(t) through B_5(t) expanded forms, if we take the coefficients of t^5
  468. * through t of the Bézier form of V(t), we can determine that:
  469. *
  470. * A = -P_0 + 5*P_1 - 10*P_2 + 10*P_3 - 5*P_4 + P_5
  471. * B = 5*P_0 - 20*P_1 + 30*P_2 - 20*P_3 + 5*P_4
  472. * C = -10*P_0 + 30*P_1 - 30*P_2 + 10*P_3
  473. * D = 10*P_0 - 20*P_1 + 10*P_2
  474. * E = - 5*P_0 + 5*P_1
  475. * F = P_0
  476. *
  477. * Now, since we will (currently) *always* want the initial acceleration and jerk values to be 0,
  478. * We set P_i = P_0 = P_1 = P_2 (initial velocity), and P_t = P_3 = P_4 = P_5 (target velocity),
  479. * which, after simplification, resolves to:
  480. *
  481. * A = - 6*P_i + 6*P_t = 6*(P_t - P_i)
  482. * B = 15*P_i - 15*P_t = 15*(P_i - P_t)
  483. * C = -10*P_i + 10*P_t = 10*(P_t - P_i)
  484. * D = 0
  485. * E = 0
  486. * F = P_i
  487. *
  488. * As the t is evaluated in non uniform steps here, there is no other way rather than evaluating
  489. * the Bézier curve at each point:
  490. *
  491. * V_f(t) = A*t^5 + B*t^4 + C*t^3 + F [0 <= t <= 1]
  492. *
  493. * Floating point arithmetic execution time cost is prohibitive, so we will transform the math to
  494. * use fixed point values to be able to evaluate it in realtime. Assuming a maximum of 250000 steps
  495. * per second (driver pulses should at least be 2µS hi/2µS lo), and allocating 2 bits to avoid
  496. * overflows on the evaluation of the Bézier curve, means we can use
  497. *
  498. * t: unsigned Q0.32 (0 <= t < 1) |range 0 to 0xFFFFFFFF unsigned
  499. * A: signed Q24.7 , |range = +/- 250000 * 6 * 128 = +/- 192000000 = 0x0B71B000 | 28 bits + sign
  500. * B: signed Q24.7 , |range = +/- 250000 *15 * 128 = +/- 480000000 = 0x1C9C3800 | 29 bits + sign
  501. * C: signed Q24.7 , |range = +/- 250000 *10 * 128 = +/- 320000000 = 0x1312D000 | 29 bits + sign
  502. * F: signed Q24.7 , |range = +/- 250000 * 128 = 32000000 = 0x01E84800 | 25 bits + sign
  503. *
  504. * The trapezoid generator state contains the following information, that we will use to create and evaluate
  505. * the Bézier curve:
  506. *
  507. * blk->step_event_count [TS] = The total count of steps for this movement. (=distance)
  508. * blk->initial_rate [VI] = The initial steps per second (=velocity)
  509. * blk->final_rate [VF] = The ending steps per second (=velocity)
  510. * and the count of events completed (step_events_completed) [CS] (=distance until now)
  511. *
  512. * Note the abbreviations we use in the following formulae are between []s
  513. *
  514. * For Any 32bit CPU:
  515. *
  516. * At the start of each trapezoid, calculate the coefficients A,B,C,F and Advance [AV], as follows:
  517. *
  518. * A = 6*128*(VF - VI) = 768*(VF - VI)
  519. * B = 15*128*(VI - VF) = 1920*(VI - VF)
  520. * C = 10*128*(VF - VI) = 1280*(VF - VI)
  521. * F = 128*VI = 128*VI
  522. * AV = (1<<32)/TS ~= 0xFFFFFFFF / TS (To use ARM UDIV, that is 32 bits) (this is computed at the planner, to offload expensive calculations from the ISR)
  523. *
  524. * And for each point, evaluate the curve with the following sequence:
  525. *
  526. * void lsrs(uint32_t& d, uint32_t s, int cnt) {
  527. * d = s >> cnt;
  528. * }
  529. * void lsls(uint32_t& d, uint32_t s, int cnt) {
  530. * d = s << cnt;
  531. * }
  532. * void lsrs(int32_t& d, uint32_t s, int cnt) {
  533. * d = uint32_t(s) >> cnt;
  534. * }
  535. * void lsls(int32_t& d, uint32_t s, int cnt) {
  536. * d = uint32_t(s) << cnt;
  537. * }
  538. * void umull(uint32_t& rlo, uint32_t& rhi, uint32_t op1, uint32_t op2) {
  539. * uint64_t res = uint64_t(op1) * op2;
  540. * rlo = uint32_t(res & 0xFFFFFFFF);
  541. * rhi = uint32_t((res >> 32) & 0xFFFFFFFF);
  542. * }
  543. * void smlal(int32_t& rlo, int32_t& rhi, int32_t op1, int32_t op2) {
  544. * int64_t mul = int64_t(op1) * op2;
  545. * int64_t s = int64_t(uint32_t(rlo) | ((uint64_t(uint32_t(rhi)) << 32U)));
  546. * mul += s;
  547. * rlo = int32_t(mul & 0xFFFFFFFF);
  548. * rhi = int32_t((mul >> 32) & 0xFFFFFFFF);
  549. * }
  550. * int32_t _eval_bezier_curve_arm(uint32_t curr_step) {
  551. * uint32_t flo = 0;
  552. * uint32_t fhi = bezier_AV * curr_step;
  553. * uint32_t t = fhi;
  554. * int32_t alo = bezier_F;
  555. * int32_t ahi = 0;
  556. * int32_t A = bezier_A;
  557. * int32_t B = bezier_B;
  558. * int32_t C = bezier_C;
  559. *
  560. * lsrs(ahi, alo, 1); // a = F << 31
  561. * lsls(alo, alo, 31); //
  562. * umull(flo, fhi, fhi, t); // f *= t
  563. * umull(flo, fhi, fhi, t); // f>>=32; f*=t
  564. * lsrs(flo, fhi, 1); //
  565. * smlal(alo, ahi, flo, C); // a+=(f>>33)*C
  566. * umull(flo, fhi, fhi, t); // f>>=32; f*=t
  567. * lsrs(flo, fhi, 1); //
  568. * smlal(alo, ahi, flo, B); // a+=(f>>33)*B
  569. * umull(flo, fhi, fhi, t); // f>>=32; f*=t
  570. * lsrs(flo, fhi, 1); // f>>=33;
  571. * smlal(alo, ahi, flo, A); // a+=(f>>33)*A;
  572. * lsrs(alo, ahi, 6); // a>>=38
  573. *
  574. * return alo;
  575. * }
  576. *
  577. * This is rewritten in ARM assembly for optimal performance (43 cycles to execute).
  578. *
  579. * For AVR, the precision of coefficients is scaled so the Bézier curve can be evaluated in real-time:
  580. * Let's reduce precision as much as possible. After some experimentation we found that:
  581. *
  582. * Assume t and AV with 24 bits is enough
  583. * A = 6*(VF - VI)
  584. * B = 15*(VI - VF)
  585. * C = 10*(VF - VI)
  586. * F = VI
  587. * AV = (1<<24)/TS (this is computed at the planner, to offload expensive calculations from the ISR)
  588. *
  589. * Instead of storing sign for each coefficient, we will store its absolute value,
  590. * and flag the sign of the A coefficient, so we can save to store the sign bit.
  591. * It always holds that sign(A) = - sign(B) = sign(C)
  592. *
  593. * So, the resulting range of the coefficients are:
  594. *
  595. * t: unsigned (0 <= t < 1) |range 0 to 0xFFFFFF unsigned
  596. * A: signed Q24 , range = 250000 * 6 = 1500000 = 0x16E360 | 21 bits
  597. * B: signed Q24 , range = 250000 *15 = 3750000 = 0x393870 | 22 bits
  598. * C: signed Q24 , range = 250000 *10 = 2500000 = 0x1312D0 | 21 bits
  599. * F: signed Q24 , range = 250000 = 250000 = 0x0ED090 | 20 bits
  600. *
  601. * And for each curve, estimate its coefficients with:
  602. *
  603. * void _calc_bezier_curve_coeffs(int32_t v0, int32_t v1, uint32_t av) {
  604. * // Calculate the Bézier coefficients
  605. * if (v1 < v0) {
  606. * A_negative = true;
  607. * bezier_A = 6 * (v0 - v1);
  608. * bezier_B = 15 * (v0 - v1);
  609. * bezier_C = 10 * (v0 - v1);
  610. * }
  611. * else {
  612. * A_negative = false;
  613. * bezier_A = 6 * (v1 - v0);
  614. * bezier_B = 15 * (v1 - v0);
  615. * bezier_C = 10 * (v1 - v0);
  616. * }
  617. * bezier_F = v0;
  618. * }
  619. *
  620. * And for each point, evaluate the curve with the following sequence:
  621. *
  622. * // unsigned multiplication of 24 bits x 24bits, return upper 16 bits
  623. * void umul24x24to16hi(uint16_t& r, uint24_t op1, uint24_t op2) {
  624. * r = (uint64_t(op1) * op2) >> 8;
  625. * }
  626. * // unsigned multiplication of 16 bits x 16bits, return upper 16 bits
  627. * void umul16x16to16hi(uint16_t& r, uint16_t op1, uint16_t op2) {
  628. * r = (uint32_t(op1) * op2) >> 16;
  629. * }
  630. * // unsigned multiplication of 16 bits x 24bits, return upper 24 bits
  631. * void umul16x24to24hi(uint24_t& r, uint16_t op1, uint24_t op2) {
  632. * r = uint24_t((uint64_t(op1) * op2) >> 16);
  633. * }
  634. *
  635. * int32_t _eval_bezier_curve(uint32_t curr_step) {
  636. * // To save computing, the first step is always the initial speed
  637. * if (!curr_step)
  638. * return bezier_F;
  639. *
  640. * uint16_t t;
  641. * umul24x24to16hi(t, bezier_AV, curr_step); // t: Range 0 - 1^16 = 16 bits
  642. * uint16_t f = t;
  643. * umul16x16to16hi(f, f, t); // Range 16 bits (unsigned)
  644. * umul16x16to16hi(f, f, t); // Range 16 bits : f = t^3 (unsigned)
  645. * uint24_t acc = bezier_F; // Range 20 bits (unsigned)
  646. * if (A_negative) {
  647. * uint24_t v;
  648. * umul16x24to24hi(v, f, bezier_C); // Range 21bits
  649. * acc -= v;
  650. * umul16x16to16hi(f, f, t); // Range 16 bits : f = t^4 (unsigned)
  651. * umul16x24to24hi(v, f, bezier_B); // Range 22bits
  652. * acc += v;
  653. * umul16x16to16hi(f, f, t); // Range 16 bits : f = t^5 (unsigned)
  654. * umul16x24to24hi(v, f, bezier_A); // Range 21bits + 15 = 36bits (plus sign)
  655. * acc -= v;
  656. * }
  657. * else {
  658. * uint24_t v;
  659. * umul16x24to24hi(v, f, bezier_C); // Range 21bits
  660. * acc += v;
  661. * umul16x16to16hi(f, f, t); // Range 16 bits : f = t^4 (unsigned)
  662. * umul16x24to24hi(v, f, bezier_B); // Range 22bits
  663. * acc -= v;
  664. * umul16x16to16hi(f, f, t); // Range 16 bits : f = t^5 (unsigned)
  665. * umul16x24to24hi(v, f, bezier_A); // Range 21bits + 15 = 36bits (plus sign)
  666. * acc += v;
  667. * }
  668. * return acc;
  669. * }
  670. * These functions are translated to assembler for optimal performance.
  671. * Coefficient calculation takes 70 cycles. Bezier point evaluation takes 150 cycles.
  672. */
  673. #ifdef __AVR__
  674. // For AVR we use assembly to maximize speed
  675. void Stepper::_calc_bezier_curve_coeffs(const int32_t v0, const int32_t v1, const uint32_t av) {
  676. // Store advance
  677. bezier_AV = av;
  678. // Calculate the rest of the coefficients
  679. uint8_t r2 = v0 & 0xFF;
  680. uint8_t r3 = (v0 >> 8) & 0xFF;
  681. uint8_t r12 = (v0 >> 16) & 0xFF;
  682. uint8_t r5 = v1 & 0xFF;
  683. uint8_t r6 = (v1 >> 8) & 0xFF;
  684. uint8_t r7 = (v1 >> 16) & 0xFF;
  685. uint8_t r4,r8,r9,r10,r11;
  686. __asm__ __volatile__(
  687. /* Calculate the Bézier coefficients */
  688. /* %10:%1:%0 = v0*/
  689. /* %5:%4:%3 = v1*/
  690. /* %7:%6:%10 = temporary*/
  691. /* %9 = val (must be high register!)*/
  692. /* %10 (must be high register!)*/
  693. /* Store initial velocity*/
  694. A("sts bezier_F, %0")
  695. A("sts bezier_F+1, %1")
  696. A("sts bezier_F+2, %10") /* bezier_F = %10:%1:%0 = v0 */
  697. /* Get delta speed */
  698. A("ldi %2,-1") /* %2 = 0xFF, means A_negative = true */
  699. A("clr %8") /* %8 = 0 */
  700. A("sub %0,%3")
  701. A("sbc %1,%4")
  702. A("sbc %10,%5") /* v0 -= v1, C=1 if result is negative */
  703. A("brcc 1f") /* branch if result is positive (C=0), that means v0 >= v1 */
  704. /* Result was negative, get the absolute value*/
  705. A("com %10")
  706. A("com %1")
  707. A("neg %0")
  708. A("sbc %1,%2")
  709. A("sbc %10,%2") /* %10:%1:%0 +1 -> %10:%1:%0 = -(v0 - v1) = (v1 - v0) */
  710. A("clr %2") /* %2 = 0, means A_negative = false */
  711. /* Store negative flag*/
  712. L("1")
  713. A("sts A_negative, %2") /* Store negative flag */
  714. /* Compute coefficients A,B and C [20 cycles worst case]*/
  715. A("ldi %9,6") /* %9 = 6 */
  716. A("mul %0,%9") /* r1:r0 = 6*LO(v0-v1) */
  717. A("sts bezier_A, r0")
  718. A("mov %6,r1")
  719. A("clr %7") /* %7:%6:r0 = 6*LO(v0-v1) */
  720. A("mul %1,%9") /* r1:r0 = 6*MI(v0-v1) */
  721. A("add %6,r0")
  722. A("adc %7,r1") /* %7:%6:?? += 6*MI(v0-v1) << 8 */
  723. A("mul %10,%9") /* r1:r0 = 6*HI(v0-v1) */
  724. A("add %7,r0") /* %7:%6:?? += 6*HI(v0-v1) << 16 */
  725. A("sts bezier_A+1, %6")
  726. A("sts bezier_A+2, %7") /* bezier_A = %7:%6:?? = 6*(v0-v1) [35 cycles worst] */
  727. A("ldi %9,15") /* %9 = 15 */
  728. A("mul %0,%9") /* r1:r0 = 5*LO(v0-v1) */
  729. A("sts bezier_B, r0")
  730. A("mov %6,r1")
  731. A("clr %7") /* %7:%6:?? = 5*LO(v0-v1) */
  732. A("mul %1,%9") /* r1:r0 = 5*MI(v0-v1) */
  733. A("add %6,r0")
  734. A("adc %7,r1") /* %7:%6:?? += 5*MI(v0-v1) << 8 */
  735. A("mul %10,%9") /* r1:r0 = 5*HI(v0-v1) */
  736. A("add %7,r0") /* %7:%6:?? += 5*HI(v0-v1) << 16 */
  737. A("sts bezier_B+1, %6")
  738. A("sts bezier_B+2, %7") /* bezier_B = %7:%6:?? = 5*(v0-v1) [50 cycles worst] */
  739. A("ldi %9,10") /* %9 = 10 */
  740. A("mul %0,%9") /* r1:r0 = 10*LO(v0-v1) */
  741. A("sts bezier_C, r0")
  742. A("mov %6,r1")
  743. A("clr %7") /* %7:%6:?? = 10*LO(v0-v1) */
  744. A("mul %1,%9") /* r1:r0 = 10*MI(v0-v1) */
  745. A("add %6,r0")
  746. A("adc %7,r1") /* %7:%6:?? += 10*MI(v0-v1) << 8 */
  747. A("mul %10,%9") /* r1:r0 = 10*HI(v0-v1) */
  748. A("add %7,r0") /* %7:%6:?? += 10*HI(v0-v1) << 16 */
  749. A("sts bezier_C+1, %6")
  750. " sts bezier_C+2, %7" /* bezier_C = %7:%6:?? = 10*(v0-v1) [65 cycles worst] */
  751. : "+r" (r2),
  752. "+d" (r3),
  753. "=r" (r4),
  754. "+r" (r5),
  755. "+r" (r6),
  756. "+r" (r7),
  757. "=r" (r8),
  758. "=r" (r9),
  759. "=r" (r10),
  760. "=d" (r11),
  761. "+r" (r12)
  762. :
  763. : "r0", "r1", "cc", "memory"
  764. );
  765. }
  766. FORCE_INLINE int32_t Stepper::_eval_bezier_curve(const uint32_t curr_step) {
  767. // If dealing with the first step, save expensive computing and return the initial speed
  768. if (!curr_step)
  769. return bezier_F;
  770. uint8_t r0 = 0; /* Zero register */
  771. uint8_t r2 = (curr_step) & 0xFF;
  772. uint8_t r3 = (curr_step >> 8) & 0xFF;
  773. uint8_t r4 = (curr_step >> 16) & 0xFF;
  774. uint8_t r1,r5,r6,r7,r8,r9,r10,r11; /* Temporary registers */
  775. __asm__ __volatile(
  776. /* umul24x24to16hi(t, bezier_AV, curr_step); t: Range 0 - 1^16 = 16 bits*/
  777. A("lds %9,bezier_AV") /* %9 = LO(AV)*/
  778. A("mul %9,%2") /* r1:r0 = LO(bezier_AV)*LO(curr_step)*/
  779. A("mov %7,r1") /* %7 = LO(bezier_AV)*LO(curr_step) >> 8*/
  780. A("clr %8") /* %8:%7 = LO(bezier_AV)*LO(curr_step) >> 8*/
  781. A("lds %10,bezier_AV+1") /* %10 = MI(AV)*/
  782. A("mul %10,%2") /* r1:r0 = MI(bezier_AV)*LO(curr_step)*/
  783. A("add %7,r0")
  784. A("adc %8,r1") /* %8:%7 += MI(bezier_AV)*LO(curr_step)*/
  785. A("lds r1,bezier_AV+2") /* r11 = HI(AV)*/
  786. A("mul r1,%2") /* r1:r0 = HI(bezier_AV)*LO(curr_step)*/
  787. A("add %8,r0") /* %8:%7 += HI(bezier_AV)*LO(curr_step) << 8*/
  788. A("mul %9,%3") /* r1:r0 = LO(bezier_AV)*MI(curr_step)*/
  789. A("add %7,r0")
  790. A("adc %8,r1") /* %8:%7 += LO(bezier_AV)*MI(curr_step)*/
  791. A("mul %10,%3") /* r1:r0 = MI(bezier_AV)*MI(curr_step)*/
  792. A("add %8,r0") /* %8:%7 += LO(bezier_AV)*MI(curr_step) << 8*/
  793. A("mul %9,%4") /* r1:r0 = LO(bezier_AV)*HI(curr_step)*/
  794. A("add %8,r0") /* %8:%7 += LO(bezier_AV)*HI(curr_step) << 8*/
  795. /* %8:%7 = t*/
  796. /* uint16_t f = t;*/
  797. A("mov %5,%7") /* %6:%5 = f*/
  798. A("mov %6,%8")
  799. /* %6:%5 = f*/
  800. /* umul16x16to16hi(f, f, t); / Range 16 bits (unsigned) [17] */
  801. A("mul %5,%7") /* r1:r0 = LO(f) * LO(t)*/
  802. A("mov %9,r1") /* store MIL(LO(f) * LO(t)) in %9, we need it for rounding*/
  803. A("clr %10") /* %10 = 0*/
  804. A("clr %11") /* %11 = 0*/
  805. A("mul %5,%8") /* r1:r0 = LO(f) * HI(t)*/
  806. A("add %9,r0") /* %9 += LO(LO(f) * HI(t))*/
  807. A("adc %10,r1") /* %10 = HI(LO(f) * HI(t))*/
  808. A("adc %11,%0") /* %11 += carry*/
  809. A("mul %6,%7") /* r1:r0 = HI(f) * LO(t)*/
  810. A("add %9,r0") /* %9 += LO(HI(f) * LO(t))*/
  811. A("adc %10,r1") /* %10 += HI(HI(f) * LO(t)) */
  812. A("adc %11,%0") /* %11 += carry*/
  813. A("mul %6,%8") /* r1:r0 = HI(f) * HI(t)*/
  814. A("add %10,r0") /* %10 += LO(HI(f) * HI(t))*/
  815. A("adc %11,r1") /* %11 += HI(HI(f) * HI(t))*/
  816. A("mov %5,%10") /* %6:%5 = */
  817. A("mov %6,%11") /* f = %10:%11*/
  818. /* umul16x16to16hi(f, f, t); / Range 16 bits : f = t^3 (unsigned) [17]*/
  819. A("mul %5,%7") /* r1:r0 = LO(f) * LO(t)*/
  820. A("mov %1,r1") /* store MIL(LO(f) * LO(t)) in %1, we need it for rounding*/
  821. A("clr %10") /* %10 = 0*/
  822. A("clr %11") /* %11 = 0*/
  823. A("mul %5,%8") /* r1:r0 = LO(f) * HI(t)*/
  824. A("add %1,r0") /* %1 += LO(LO(f) * HI(t))*/
  825. A("adc %10,r1") /* %10 = HI(LO(f) * HI(t))*/
  826. A("adc %11,%0") /* %11 += carry*/
  827. A("mul %6,%7") /* r1:r0 = HI(f) * LO(t)*/
  828. A("add %1,r0") /* %1 += LO(HI(f) * LO(t))*/
  829. A("adc %10,r1") /* %10 += HI(HI(f) * LO(t))*/
  830. A("adc %11,%0") /* %11 += carry*/
  831. A("mul %6,%8") /* r1:r0 = HI(f) * HI(t)*/
  832. A("add %10,r0") /* %10 += LO(HI(f) * HI(t))*/
  833. A("adc %11,r1") /* %11 += HI(HI(f) * HI(t))*/
  834. A("mov %5,%10") /* %6:%5 =*/
  835. A("mov %6,%11") /* f = %10:%11*/
  836. /* [15 +17*2] = [49]*/
  837. /* %4:%3:%2 will be acc from now on*/
  838. /* uint24_t acc = bezier_F; / Range 20 bits (unsigned)*/
  839. A("clr %9") /* "decimal place we get for free"*/
  840. A("lds %2,bezier_F")
  841. A("lds %3,bezier_F+1")
  842. A("lds %4,bezier_F+2") /* %4:%3:%2 = acc*/
  843. /* if (A_negative) {*/
  844. A("lds r0,A_negative")
  845. A("or r0,%0") /* Is flag signalling negative? */
  846. A("brne 3f") /* If yes, Skip next instruction if A was negative*/
  847. A("rjmp 1f") /* Otherwise, jump */
  848. /* uint24_t v; */
  849. /* umul16x24to24hi(v, f, bezier_C); / Range 21bits [29] */
  850. /* acc -= v; */
  851. L("3")
  852. A("lds %10, bezier_C") /* %10 = LO(bezier_C)*/
  853. A("mul %10,%5") /* r1:r0 = LO(bezier_C) * LO(f)*/
  854. A("sub %9,r1")
  855. A("sbc %2,%0")
  856. A("sbc %3,%0")
  857. A("sbc %4,%0") /* %4:%3:%2:%9 -= HI(LO(bezier_C) * LO(f))*/
  858. A("lds %11, bezier_C+1") /* %11 = MI(bezier_C)*/
  859. A("mul %11,%5") /* r1:r0 = MI(bezier_C) * LO(f)*/
  860. A("sub %9,r0")
  861. A("sbc %2,r1")
  862. A("sbc %3,%0")
  863. A("sbc %4,%0") /* %4:%3:%2:%9 -= MI(bezier_C) * LO(f)*/
  864. A("lds %1, bezier_C+2") /* %1 = HI(bezier_C)*/
  865. A("mul %1,%5") /* r1:r0 = MI(bezier_C) * LO(f)*/
  866. A("sub %2,r0")
  867. A("sbc %3,r1")
  868. A("sbc %4,%0") /* %4:%3:%2:%9 -= HI(bezier_C) * LO(f) << 8*/
  869. A("mul %10,%6") /* r1:r0 = LO(bezier_C) * MI(f)*/
  870. A("sub %9,r0")
  871. A("sbc %2,r1")
  872. A("sbc %3,%0")
  873. A("sbc %4,%0") /* %4:%3:%2:%9 -= LO(bezier_C) * MI(f)*/
  874. A("mul %11,%6") /* r1:r0 = MI(bezier_C) * MI(f)*/
  875. A("sub %2,r0")
  876. A("sbc %3,r1")
  877. A("sbc %4,%0") /* %4:%3:%2:%9 -= MI(bezier_C) * MI(f) << 8*/
  878. A("mul %1,%6") /* r1:r0 = HI(bezier_C) * LO(f)*/
  879. A("sub %3,r0")
  880. A("sbc %4,r1") /* %4:%3:%2:%9 -= HI(bezier_C) * LO(f) << 16*/
  881. /* umul16x16to16hi(f, f, t); / Range 16 bits : f = t^3 (unsigned) [17]*/
  882. A("mul %5,%7") /* r1:r0 = LO(f) * LO(t)*/
  883. A("mov %1,r1") /* store MIL(LO(f) * LO(t)) in %1, we need it for rounding*/
  884. A("clr %10") /* %10 = 0*/
  885. A("clr %11") /* %11 = 0*/
  886. A("mul %5,%8") /* r1:r0 = LO(f) * HI(t)*/
  887. A("add %1,r0") /* %1 += LO(LO(f) * HI(t))*/
  888. A("adc %10,r1") /* %10 = HI(LO(f) * HI(t))*/
  889. A("adc %11,%0") /* %11 += carry*/
  890. A("mul %6,%7") /* r1:r0 = HI(f) * LO(t)*/
  891. A("add %1,r0") /* %1 += LO(HI(f) * LO(t))*/
  892. A("adc %10,r1") /* %10 += HI(HI(f) * LO(t))*/
  893. A("adc %11,%0") /* %11 += carry*/
  894. A("mul %6,%8") /* r1:r0 = HI(f) * HI(t)*/
  895. A("add %10,r0") /* %10 += LO(HI(f) * HI(t))*/
  896. A("adc %11,r1") /* %11 += HI(HI(f) * HI(t))*/
  897. A("mov %5,%10") /* %6:%5 =*/
  898. A("mov %6,%11") /* f = %10:%11*/
  899. /* umul16x24to24hi(v, f, bezier_B); / Range 22bits [29]*/
  900. /* acc += v; */
  901. A("lds %10, bezier_B") /* %10 = LO(bezier_B)*/
  902. A("mul %10,%5") /* r1:r0 = LO(bezier_B) * LO(f)*/
  903. A("add %9,r1")
  904. A("adc %2,%0")
  905. A("adc %3,%0")
  906. A("adc %4,%0") /* %4:%3:%2:%9 += HI(LO(bezier_B) * LO(f))*/
  907. A("lds %11, bezier_B+1") /* %11 = MI(bezier_B)*/
  908. A("mul %11,%5") /* r1:r0 = MI(bezier_B) * LO(f)*/
  909. A("add %9,r0")
  910. A("adc %2,r1")
  911. A("adc %3,%0")
  912. A("adc %4,%0") /* %4:%3:%2:%9 += MI(bezier_B) * LO(f)*/
  913. A("lds %1, bezier_B+2") /* %1 = HI(bezier_B)*/
  914. A("mul %1,%5") /* r1:r0 = MI(bezier_B) * LO(f)*/
  915. A("add %2,r0")
  916. A("adc %3,r1")
  917. A("adc %4,%0") /* %4:%3:%2:%9 += HI(bezier_B) * LO(f) << 8*/
  918. A("mul %10,%6") /* r1:r0 = LO(bezier_B) * MI(f)*/
  919. A("add %9,r0")
  920. A("adc %2,r1")
  921. A("adc %3,%0")
  922. A("adc %4,%0") /* %4:%3:%2:%9 += LO(bezier_B) * MI(f)*/
  923. A("mul %11,%6") /* r1:r0 = MI(bezier_B) * MI(f)*/
  924. A("add %2,r0")
  925. A("adc %3,r1")
  926. A("adc %4,%0") /* %4:%3:%2:%9 += MI(bezier_B) * MI(f) << 8*/
  927. A("mul %1,%6") /* r1:r0 = HI(bezier_B) * LO(f)*/
  928. A("add %3,r0")
  929. A("adc %4,r1") /* %4:%3:%2:%9 += HI(bezier_B) * LO(f) << 16*/
  930. /* umul16x16to16hi(f, f, t); / Range 16 bits : f = t^5 (unsigned) [17]*/
  931. A("mul %5,%7") /* r1:r0 = LO(f) * LO(t)*/
  932. A("mov %1,r1") /* store MIL(LO(f) * LO(t)) in %1, we need it for rounding*/
  933. A("clr %10") /* %10 = 0*/
  934. A("clr %11") /* %11 = 0*/
  935. A("mul %5,%8") /* r1:r0 = LO(f) * HI(t)*/
  936. A("add %1,r0") /* %1 += LO(LO(f) * HI(t))*/
  937. A("adc %10,r1") /* %10 = HI(LO(f) * HI(t))*/
  938. A("adc %11,%0") /* %11 += carry*/
  939. A("mul %6,%7") /* r1:r0 = HI(f) * LO(t)*/
  940. A("add %1,r0") /* %1 += LO(HI(f) * LO(t))*/
  941. A("adc %10,r1") /* %10 += HI(HI(f) * LO(t))*/
  942. A("adc %11,%0") /* %11 += carry*/
  943. A("mul %6,%8") /* r1:r0 = HI(f) * HI(t)*/
  944. A("add %10,r0") /* %10 += LO(HI(f) * HI(t))*/
  945. A("adc %11,r1") /* %11 += HI(HI(f) * HI(t))*/
  946. A("mov %5,%10") /* %6:%5 =*/
  947. A("mov %6,%11") /* f = %10:%11*/
  948. /* umul16x24to24hi(v, f, bezier_A); / Range 21bits [29]*/
  949. /* acc -= v; */
  950. A("lds %10, bezier_A") /* %10 = LO(bezier_A)*/
  951. A("mul %10,%5") /* r1:r0 = LO(bezier_A) * LO(f)*/
  952. A("sub %9,r1")
  953. A("sbc %2,%0")
  954. A("sbc %3,%0")
  955. A("sbc %4,%0") /* %4:%3:%2:%9 -= HI(LO(bezier_A) * LO(f))*/
  956. A("lds %11, bezier_A+1") /* %11 = MI(bezier_A)*/
  957. A("mul %11,%5") /* r1:r0 = MI(bezier_A) * LO(f)*/
  958. A("sub %9,r0")
  959. A("sbc %2,r1")
  960. A("sbc %3,%0")
  961. A("sbc %4,%0") /* %4:%3:%2:%9 -= MI(bezier_A) * LO(f)*/
  962. A("lds %1, bezier_A+2") /* %1 = HI(bezier_A)*/
  963. A("mul %1,%5") /* r1:r0 = MI(bezier_A) * LO(f)*/
  964. A("sub %2,r0")
  965. A("sbc %3,r1")
  966. A("sbc %4,%0") /* %4:%3:%2:%9 -= HI(bezier_A) * LO(f) << 8*/
  967. A("mul %10,%6") /* r1:r0 = LO(bezier_A) * MI(f)*/
  968. A("sub %9,r0")
  969. A("sbc %2,r1")
  970. A("sbc %3,%0")
  971. A("sbc %4,%0") /* %4:%3:%2:%9 -= LO(bezier_A) * MI(f)*/
  972. A("mul %11,%6") /* r1:r0 = MI(bezier_A) * MI(f)*/
  973. A("sub %2,r0")
  974. A("sbc %3,r1")
  975. A("sbc %4,%0") /* %4:%3:%2:%9 -= MI(bezier_A) * MI(f) << 8*/
  976. A("mul %1,%6") /* r1:r0 = HI(bezier_A) * LO(f)*/
  977. A("sub %3,r0")
  978. A("sbc %4,r1") /* %4:%3:%2:%9 -= HI(bezier_A) * LO(f) << 16*/
  979. A("jmp 2f") /* Done!*/
  980. L("1")
  981. /* uint24_t v; */
  982. /* umul16x24to24hi(v, f, bezier_C); / Range 21bits [29]*/
  983. /* acc += v; */
  984. A("lds %10, bezier_C") /* %10 = LO(bezier_C)*/
  985. A("mul %10,%5") /* r1:r0 = LO(bezier_C) * LO(f)*/
  986. A("add %9,r1")
  987. A("adc %2,%0")
  988. A("adc %3,%0")
  989. A("adc %4,%0") /* %4:%3:%2:%9 += HI(LO(bezier_C) * LO(f))*/
  990. A("lds %11, bezier_C+1") /* %11 = MI(bezier_C)*/
  991. A("mul %11,%5") /* r1:r0 = MI(bezier_C) * LO(f)*/
  992. A("add %9,r0")
  993. A("adc %2,r1")
  994. A("adc %3,%0")
  995. A("adc %4,%0") /* %4:%3:%2:%9 += MI(bezier_C) * LO(f)*/
  996. A("lds %1, bezier_C+2") /* %1 = HI(bezier_C)*/
  997. A("mul %1,%5") /* r1:r0 = MI(bezier_C) * LO(f)*/
  998. A("add %2,r0")
  999. A("adc %3,r1")
  1000. A("adc %4,%0") /* %4:%3:%2:%9 += HI(bezier_C) * LO(f) << 8*/
  1001. A("mul %10,%6") /* r1:r0 = LO(bezier_C) * MI(f)*/
  1002. A("add %9,r0")
  1003. A("adc %2,r1")
  1004. A("adc %3,%0")
  1005. A("adc %4,%0") /* %4:%3:%2:%9 += LO(bezier_C) * MI(f)*/
  1006. A("mul %11,%6") /* r1:r0 = MI(bezier_C) * MI(f)*/
  1007. A("add %2,r0")
  1008. A("adc %3,r1")
  1009. A("adc %4,%0") /* %4:%3:%2:%9 += MI(bezier_C) * MI(f) << 8*/
  1010. A("mul %1,%6") /* r1:r0 = HI(bezier_C) * LO(f)*/
  1011. A("add %3,r0")
  1012. A("adc %4,r1") /* %4:%3:%2:%9 += HI(bezier_C) * LO(f) << 16*/
  1013. /* umul16x16to16hi(f, f, t); / Range 16 bits : f = t^3 (unsigned) [17]*/
  1014. A("mul %5,%7") /* r1:r0 = LO(f) * LO(t)*/
  1015. A("mov %1,r1") /* store MIL(LO(f) * LO(t)) in %1, we need it for rounding*/
  1016. A("clr %10") /* %10 = 0*/
  1017. A("clr %11") /* %11 = 0*/
  1018. A("mul %5,%8") /* r1:r0 = LO(f) * HI(t)*/
  1019. A("add %1,r0") /* %1 += LO(LO(f) * HI(t))*/
  1020. A("adc %10,r1") /* %10 = HI(LO(f) * HI(t))*/
  1021. A("adc %11,%0") /* %11 += carry*/
  1022. A("mul %6,%7") /* r1:r0 = HI(f) * LO(t)*/
  1023. A("add %1,r0") /* %1 += LO(HI(f) * LO(t))*/
  1024. A("adc %10,r1") /* %10 += HI(HI(f) * LO(t))*/
  1025. A("adc %11,%0") /* %11 += carry*/
  1026. A("mul %6,%8") /* r1:r0 = HI(f) * HI(t)*/
  1027. A("add %10,r0") /* %10 += LO(HI(f) * HI(t))*/
  1028. A("adc %11,r1") /* %11 += HI(HI(f) * HI(t))*/
  1029. A("mov %5,%10") /* %6:%5 =*/
  1030. A("mov %6,%11") /* f = %10:%11*/
  1031. /* umul16x24to24hi(v, f, bezier_B); / Range 22bits [29]*/
  1032. /* acc -= v;*/
  1033. A("lds %10, bezier_B") /* %10 = LO(bezier_B)*/
  1034. A("mul %10,%5") /* r1:r0 = LO(bezier_B) * LO(f)*/
  1035. A("sub %9,r1")
  1036. A("sbc %2,%0")
  1037. A("sbc %3,%0")
  1038. A("sbc %4,%0") /* %4:%3:%2:%9 -= HI(LO(bezier_B) * LO(f))*/
  1039. A("lds %11, bezier_B+1") /* %11 = MI(bezier_B)*/
  1040. A("mul %11,%5") /* r1:r0 = MI(bezier_B) * LO(f)*/
  1041. A("sub %9,r0")
  1042. A("sbc %2,r1")
  1043. A("sbc %3,%0")
  1044. A("sbc %4,%0") /* %4:%3:%2:%9 -= MI(bezier_B) * LO(f)*/
  1045. A("lds %1, bezier_B+2") /* %1 = HI(bezier_B)*/
  1046. A("mul %1,%5") /* r1:r0 = MI(bezier_B) * LO(f)*/
  1047. A("sub %2,r0")
  1048. A("sbc %3,r1")
  1049. A("sbc %4,%0") /* %4:%3:%2:%9 -= HI(bezier_B) * LO(f) << 8*/
  1050. A("mul %10,%6") /* r1:r0 = LO(bezier_B) * MI(f)*/
  1051. A("sub %9,r0")
  1052. A("sbc %2,r1")
  1053. A("sbc %3,%0")
  1054. A("sbc %4,%0") /* %4:%3:%2:%9 -= LO(bezier_B) * MI(f)*/
  1055. A("mul %11,%6") /* r1:r0 = MI(bezier_B) * MI(f)*/
  1056. A("sub %2,r0")
  1057. A("sbc %3,r1")
  1058. A("sbc %4,%0") /* %4:%3:%2:%9 -= MI(bezier_B) * MI(f) << 8*/
  1059. A("mul %1,%6") /* r1:r0 = HI(bezier_B) * LO(f)*/
  1060. A("sub %3,r0")
  1061. A("sbc %4,r1") /* %4:%3:%2:%9 -= HI(bezier_B) * LO(f) << 16*/
  1062. /* umul16x16to16hi(f, f, t); / Range 16 bits : f = t^5 (unsigned) [17]*/
  1063. A("mul %5,%7") /* r1:r0 = LO(f) * LO(t)*/
  1064. A("mov %1,r1") /* store MIL(LO(f) * LO(t)) in %1, we need it for rounding*/
  1065. A("clr %10") /* %10 = 0*/
  1066. A("clr %11") /* %11 = 0*/
  1067. A("mul %5,%8") /* r1:r0 = LO(f) * HI(t)*/
  1068. A("add %1,r0") /* %1 += LO(LO(f) * HI(t))*/
  1069. A("adc %10,r1") /* %10 = HI(LO(f) * HI(t))*/
  1070. A("adc %11,%0") /* %11 += carry*/
  1071. A("mul %6,%7") /* r1:r0 = HI(f) * LO(t)*/
  1072. A("add %1,r0") /* %1 += LO(HI(f) * LO(t))*/
  1073. A("adc %10,r1") /* %10 += HI(HI(f) * LO(t))*/
  1074. A("adc %11,%0") /* %11 += carry*/
  1075. A("mul %6,%8") /* r1:r0 = HI(f) * HI(t)*/
  1076. A("add %10,r0") /* %10 += LO(HI(f) * HI(t))*/
  1077. A("adc %11,r1") /* %11 += HI(HI(f) * HI(t))*/
  1078. A("mov %5,%10") /* %6:%5 =*/
  1079. A("mov %6,%11") /* f = %10:%11*/
  1080. /* umul16x24to24hi(v, f, bezier_A); / Range 21bits [29]*/
  1081. /* acc += v; */
  1082. A("lds %10, bezier_A") /* %10 = LO(bezier_A)*/
  1083. A("mul %10,%5") /* r1:r0 = LO(bezier_A) * LO(f)*/
  1084. A("add %9,r1")
  1085. A("adc %2,%0")
  1086. A("adc %3,%0")
  1087. A("adc %4,%0") /* %4:%3:%2:%9 += HI(LO(bezier_A) * LO(f))*/
  1088. A("lds %11, bezier_A+1") /* %11 = MI(bezier_A)*/
  1089. A("mul %11,%5") /* r1:r0 = MI(bezier_A) * LO(f)*/
  1090. A("add %9,r0")
  1091. A("adc %2,r1")
  1092. A("adc %3,%0")
  1093. A("adc %4,%0") /* %4:%3:%2:%9 += MI(bezier_A) * LO(f)*/
  1094. A("lds %1, bezier_A+2") /* %1 = HI(bezier_A)*/
  1095. A("mul %1,%5") /* r1:r0 = MI(bezier_A) * LO(f)*/
  1096. A("add %2,r0")
  1097. A("adc %3,r1")
  1098. A("adc %4,%0") /* %4:%3:%2:%9 += HI(bezier_A) * LO(f) << 8*/
  1099. A("mul %10,%6") /* r1:r0 = LO(bezier_A) * MI(f)*/
  1100. A("add %9,r0")
  1101. A("adc %2,r1")
  1102. A("adc %3,%0")
  1103. A("adc %4,%0") /* %4:%3:%2:%9 += LO(bezier_A) * MI(f)*/
  1104. A("mul %11,%6") /* r1:r0 = MI(bezier_A) * MI(f)*/
  1105. A("add %2,r0")
  1106. A("adc %3,r1")
  1107. A("adc %4,%0") /* %4:%3:%2:%9 += MI(bezier_A) * MI(f) << 8*/
  1108. A("mul %1,%6") /* r1:r0 = HI(bezier_A) * LO(f)*/
  1109. A("add %3,r0")
  1110. A("adc %4,r1") /* %4:%3:%2:%9 += HI(bezier_A) * LO(f) << 16*/
  1111. L("2")
  1112. " clr __zero_reg__" /* C runtime expects r1 = __zero_reg__ = 0 */
  1113. : "+r"(r0),
  1114. "+r"(r1),
  1115. "+r"(r2),
  1116. "+r"(r3),
  1117. "+r"(r4),
  1118. "+r"(r5),
  1119. "+r"(r6),
  1120. "+r"(r7),
  1121. "+r"(r8),
  1122. "+r"(r9),
  1123. "+r"(r10),
  1124. "+r"(r11)
  1125. :
  1126. :"cc","r0","r1"
  1127. );
  1128. return (r2 | (uint16_t(r3) << 8)) | (uint32_t(r4) << 16);
  1129. }
  1130. #else
  1131. // For all the other 32bit CPUs
  1132. FORCE_INLINE void Stepper::_calc_bezier_curve_coeffs(const int32_t v0, const int32_t v1, const uint32_t av) {
  1133. // Calculate the Bézier coefficients
  1134. bezier_A = 768 * (v1 - v0);
  1135. bezier_B = 1920 * (v0 - v1);
  1136. bezier_C = 1280 * (v1 - v0);
  1137. bezier_F = 128 * v0;
  1138. bezier_AV = av;
  1139. }
  1140. FORCE_INLINE int32_t Stepper::_eval_bezier_curve(const uint32_t curr_step) {
  1141. #if defined(__ARM__) || defined(__thumb__)
  1142. // For ARM Cortex M3/M4 CPUs, we have the optimized assembler version, that takes 43 cycles to execute
  1143. uint32_t flo = 0;
  1144. uint32_t fhi = bezier_AV * curr_step;
  1145. uint32_t t = fhi;
  1146. int32_t alo = bezier_F;
  1147. int32_t ahi = 0;
  1148. int32_t A = bezier_A;
  1149. int32_t B = bezier_B;
  1150. int32_t C = bezier_C;
  1151. __asm__ __volatile__(
  1152. ".syntax unified" "\n\t" // is to prevent CM0,CM1 non-unified syntax
  1153. A("lsrs %[ahi],%[alo],#1") // a = F << 31 1 cycles
  1154. A("lsls %[alo],%[alo],#31") // 1 cycles
  1155. A("umull %[flo],%[fhi],%[fhi],%[t]") // f *= t 5 cycles [fhi:flo=64bits]
  1156. A("umull %[flo],%[fhi],%[fhi],%[t]") // f>>=32; f*=t 5 cycles [fhi:flo=64bits]
  1157. A("lsrs %[flo],%[fhi],#1") // 1 cycles [31bits]
  1158. A("smlal %[alo],%[ahi],%[flo],%[C]") // a+=(f>>33)*C; 5 cycles
  1159. A("umull %[flo],%[fhi],%[fhi],%[t]") // f>>=32; f*=t 5 cycles [fhi:flo=64bits]
  1160. A("lsrs %[flo],%[fhi],#1") // 1 cycles [31bits]
  1161. A("smlal %[alo],%[ahi],%[flo],%[B]") // a+=(f>>33)*B; 5 cycles
  1162. A("umull %[flo],%[fhi],%[fhi],%[t]") // f>>=32; f*=t 5 cycles [fhi:flo=64bits]
  1163. A("lsrs %[flo],%[fhi],#1") // f>>=33; 1 cycles [31bits]
  1164. A("smlal %[alo],%[ahi],%[flo],%[A]") // a+=(f>>33)*A; 5 cycles
  1165. A("lsrs %[alo],%[ahi],#6") // a>>=38 1 cycles
  1166. : [alo]"+r"( alo ) ,
  1167. [flo]"+r"( flo ) ,
  1168. [fhi]"+r"( fhi ) ,
  1169. [ahi]"+r"( ahi ) ,
  1170. [A]"+r"( A ) , // <== Note: Even if A, B, C, and t registers are INPUT ONLY
  1171. [B]"+r"( B ) , // GCC does bad optimizations on the code if we list them as
  1172. [C]"+r"( C ) , // such, breaking this function. So, to avoid that problem,
  1173. [t]"+r"( t ) // we list all registers as input-outputs.
  1174. :
  1175. : "cc"
  1176. );
  1177. return alo;
  1178. #else
  1179. // For non ARM targets, we provide a fallback implementation. Really doubt it
  1180. // will be useful, unless the processor is fast and 32bit
  1181. uint32_t t = bezier_AV * curr_step; // t: Range 0 - 1^32 = 32 bits
  1182. uint64_t f = t;
  1183. f *= t; // Range 32*2 = 64 bits (unsigned)
  1184. f >>= 32; // Range 32 bits (unsigned)
  1185. f *= t; // Range 32*2 = 64 bits (unsigned)
  1186. f >>= 32; // Range 32 bits : f = t^3 (unsigned)
  1187. int64_t acc = (int64_t) bezier_F << 31; // Range 63 bits (signed)
  1188. acc += ((uint32_t) f >> 1) * (int64_t) bezier_C; // Range 29bits + 31 = 60bits (plus sign)
  1189. f *= t; // Range 32*2 = 64 bits
  1190. f >>= 32; // Range 32 bits : f = t^3 (unsigned)
  1191. acc += ((uint32_t) f >> 1) * (int64_t) bezier_B; // Range 29bits + 31 = 60bits (plus sign)
  1192. f *= t; // Range 32*2 = 64 bits
  1193. f >>= 32; // Range 32 bits : f = t^3 (unsigned)
  1194. acc += ((uint32_t) f >> 1) * (int64_t) bezier_A; // Range 28bits + 31 = 59bits (plus sign)
  1195. acc >>= (31 + 7); // Range 24bits (plus sign)
  1196. return (int32_t) acc;
  1197. #endif
  1198. }
  1199. #endif
  1200. #endif // S_CURVE_ACCELERATION
  1201. /**
  1202. * Stepper Driver Interrupt
  1203. *
  1204. * Directly pulses the stepper motors at high frequency.
  1205. */
  1206. HAL_STEP_TIMER_ISR() {
  1207. HAL_timer_isr_prologue(STEP_TIMER_NUM);
  1208. Stepper::isr();
  1209. HAL_timer_isr_epilogue(STEP_TIMER_NUM);
  1210. }
  1211. #ifdef CPU_32_BIT
  1212. #define STEP_MULTIPLY(A,B) MultiU32X24toH32(A, B)
  1213. #else
  1214. #define STEP_MULTIPLY(A,B) MultiU24X32toH16(A, B)
  1215. #endif
  1216. void Stepper::isr() {
  1217. static uint32_t nextMainISR = 0; // Interval until the next main Stepper Pulse phase (0 = Now)
  1218. #ifndef __AVR__
  1219. // Disable interrupts, to avoid ISR preemption while we reprogram the period
  1220. // (AVR enters the ISR with global interrupts disabled, so no need to do it here)
  1221. DISABLE_ISRS();
  1222. #endif
  1223. // Program timer compare for the maximum period, so it does NOT
  1224. // flag an interrupt while this ISR is running - So changes from small
  1225. // periods to big periods are respected and the timer does not reset to 0
  1226. HAL_timer_set_compare(STEP_TIMER_NUM, hal_timer_t(HAL_TIMER_TYPE_MAX));
  1227. // Count of ticks for the next ISR
  1228. hal_timer_t next_isr_ticks = 0;
  1229. // Limit the amount of iterations
  1230. uint8_t max_loops = 10;
  1231. // We need this variable here to be able to use it in the following loop
  1232. hal_timer_t min_ticks;
  1233. do {
  1234. // Enable ISRs to reduce USART processing latency
  1235. ENABLE_ISRS();
  1236. if (!nextMainISR) pulse_phase_isr(); // 0 = Do coordinated axes Stepper pulses
  1237. #if ENABLED(LIN_ADVANCE)
  1238. if (!nextAdvanceISR) nextAdvanceISR = advance_isr(); // 0 = Do Linear Advance E Stepper pulses
  1239. #endif
  1240. #if ENABLED(INTEGRATED_BABYSTEPPING)
  1241. const bool do_babystep = (nextBabystepISR == 0); // 0 = Do Babystepping (XY)Z pulses
  1242. if (do_babystep) nextBabystepISR = babystepping_isr();
  1243. #endif
  1244. // ^== Time critical. NOTHING besides pulse generation should be above here!!!
  1245. if (!nextMainISR) nextMainISR = block_phase_isr(); // Manage acc/deceleration, get next block
  1246. #if ENABLED(INTEGRATED_BABYSTEPPING)
  1247. if (do_babystep) // Avoid ANY stepping too soon after baby-stepping
  1248. NOLESS(nextMainISR, (BABYSTEP_TICKS) / 8); // FULL STOP for 125µs after a baby-step
  1249. if (nextBabystepISR != BABYSTEP_NEVER) // Avoid baby-stepping too close to axis Stepping
  1250. NOLESS(nextBabystepISR, nextMainISR / 2); // TODO: Only look at axes enabled for baby-stepping
  1251. #endif
  1252. // Get the interval to the next ISR call
  1253. const uint32_t interval = _MIN(
  1254. nextMainISR // Time until the next Pulse / Block phase
  1255. #if ENABLED(LIN_ADVANCE)
  1256. , nextAdvanceISR // Come back early for Linear Advance?
  1257. #endif
  1258. #if ENABLED(INTEGRATED_BABYSTEPPING)
  1259. , nextBabystepISR // Come back early for Babystepping?
  1260. #endif
  1261. , uint32_t(HAL_TIMER_TYPE_MAX) // Come back in a very long time
  1262. );
  1263. //
  1264. // Compute remaining time for each ISR phase
  1265. // NEVER : The phase is idle
  1266. // Zero : The phase will occur on the next ISR call
  1267. // Non-zero : The phase will occur on a future ISR call
  1268. //
  1269. nextMainISR -= interval;
  1270. #if ENABLED(LIN_ADVANCE)
  1271. if (nextAdvanceISR != LA_ADV_NEVER) nextAdvanceISR -= interval;
  1272. #endif
  1273. #if ENABLED(INTEGRATED_BABYSTEPPING)
  1274. if (nextBabystepISR != BABYSTEP_NEVER) nextBabystepISR -= interval;
  1275. #endif
  1276. /**
  1277. * This needs to avoid a race-condition caused by interleaving
  1278. * of interrupts required by both the LA and Stepper algorithms.
  1279. *
  1280. * Assume the following tick times for stepper pulses:
  1281. * Stepper ISR (S): 1 1000 2000 3000 4000
  1282. * Linear Adv. (E): 10 1010 2010 3010 4010
  1283. *
  1284. * The current algorithm tries to interleave them, giving:
  1285. * 1:S 10:E 1000:S 1010:E 2000:S 2010:E 3000:S 3010:E 4000:S 4010:E
  1286. *
  1287. * Ideal timing would yield these delta periods:
  1288. * 1:S 9:E 990:S 10:E 990:S 10:E 990:S 10:E 990:S 10:E
  1289. *
  1290. * But, since each event must fire an ISR with a minimum duration, the
  1291. * minimum delta might be 900, so deltas under 900 get rounded up:
  1292. * 900:S d900:E d990:S d900:E d990:S d900:E d990:S d900:E d990:S d900:E
  1293. *
  1294. * It works, but divides the speed of all motors by half, leading to a sudden
  1295. * reduction to 1/2 speed! Such jumps in speed lead to lost steps (not even
  1296. * accounting for double/quad stepping, which makes it even worse).
  1297. */
  1298. // Compute the tick count for the next ISR
  1299. next_isr_ticks += interval;
  1300. /**
  1301. * The following section must be done with global interrupts disabled.
  1302. * We want nothing to interrupt it, as that could mess the calculations
  1303. * we do for the next value to program in the period register of the
  1304. * stepper timer and lead to skipped ISRs (if the value we happen to program
  1305. * is less than the current count due to something preempting between the
  1306. * read and the write of the new period value).
  1307. */
  1308. DISABLE_ISRS();
  1309. /**
  1310. * Get the current tick value + margin
  1311. * Assuming at least 6µs between calls to this ISR...
  1312. * On AVR the ISR epilogue+prologue is estimated at 100 instructions - Give 8µs as margin
  1313. * On ARM the ISR epilogue+prologue is estimated at 20 instructions - Give 1µs as margin
  1314. */
  1315. min_ticks = HAL_timer_get_count(STEP_TIMER_NUM) + hal_timer_t(
  1316. #ifdef __AVR__
  1317. 8
  1318. #else
  1319. 1
  1320. #endif
  1321. * (STEPPER_TIMER_TICKS_PER_US)
  1322. );
  1323. /**
  1324. * NB: If for some reason the stepper monopolizes the MPU, eventually the
  1325. * timer will wrap around (and so will 'next_isr_ticks'). So, limit the
  1326. * loop to 10 iterations. Beyond that, there's no way to ensure correct pulse
  1327. * timing, since the MCU isn't fast enough.
  1328. */
  1329. if (!--max_loops) next_isr_ticks = min_ticks;
  1330. // Advance pulses if not enough time to wait for the next ISR
  1331. } while (next_isr_ticks < min_ticks);
  1332. // Now 'next_isr_ticks' contains the period to the next Stepper ISR - And we are
  1333. // sure that the time has not arrived yet - Warrantied by the scheduler
  1334. // Set the next ISR to fire at the proper time
  1335. HAL_timer_set_compare(STEP_TIMER_NUM, hal_timer_t(next_isr_ticks));
  1336. // Don't forget to finally reenable interrupts
  1337. ENABLE_ISRS();
  1338. }
  1339. #define ISR_PULSE_CONTROL (MINIMUM_STEPPER_PULSE || MAXIMUM_STEPPER_RATE)
  1340. #define ISR_MULTI_STEPS (ISR_PULSE_CONTROL && DISABLED(I2S_STEPPER_STREAM))
  1341. /**
  1342. * This phase of the ISR should ONLY create the pulses for the steppers.
  1343. * This prevents jitter caused by the interval between the start of the
  1344. * interrupt and the start of the pulses. DON'T add any logic ahead of the
  1345. * call to this method that might cause variation in the timing. The aim
  1346. * is to keep pulse timing as regular as possible.
  1347. */
  1348. void Stepper::pulse_phase_isr() {
  1349. // If we must abort the current block, do so!
  1350. if (abort_current_block) {
  1351. abort_current_block = false;
  1352. if (current_block) {
  1353. axis_did_move = 0;
  1354. current_block = nullptr;
  1355. planner.discard_current_block();
  1356. }
  1357. }
  1358. // If there is no current block, do nothing
  1359. if (!current_block) return;
  1360. // Count of pending loops and events for this iteration
  1361. const uint32_t pending_events = step_event_count - step_events_completed;
  1362. uint8_t events_to_do = _MIN(pending_events, steps_per_isr);
  1363. // Just update the value we will get at the end of the loop
  1364. step_events_completed += events_to_do;
  1365. // Take multiple steps per interrupt (For high speed moves)
  1366. #if ISR_MULTI_STEPS
  1367. bool firstStep = true;
  1368. USING_TIMED_PULSE();
  1369. #endif
  1370. xyze_bool_t step_needed{0};
  1371. do {
  1372. #define _APPLY_STEP(AXIS, INV, ALWAYS) AXIS ##_APPLY_STEP(INV, ALWAYS)
  1373. #define _INVERT_STEP_PIN(AXIS) INVERT_## AXIS ##_STEP_PIN
  1374. // Determine if a pulse is needed using Bresenham
  1375. #define PULSE_PREP(AXIS) do{ \
  1376. delta_error[_AXIS(AXIS)] += advance_dividend[_AXIS(AXIS)]; \
  1377. step_needed[_AXIS(AXIS)] = (delta_error[_AXIS(AXIS)] >= 0); \
  1378. if (step_needed[_AXIS(AXIS)]) { \
  1379. count_position[_AXIS(AXIS)] += count_direction[_AXIS(AXIS)]; \
  1380. delta_error[_AXIS(AXIS)] -= advance_divisor; \
  1381. } \
  1382. }while(0)
  1383. // Start an active pulse, if Bresenham says so, and update position
  1384. #define PULSE_START(AXIS) do{ \
  1385. if (step_needed[_AXIS(AXIS)]) { \
  1386. _APPLY_STEP(AXIS, !_INVERT_STEP_PIN(AXIS), 0); \
  1387. } \
  1388. }while(0)
  1389. // Stop an active pulse, if any, and adjust error term
  1390. #define PULSE_STOP(AXIS) do { \
  1391. if (step_needed[_AXIS(AXIS)]) { \
  1392. _APPLY_STEP(AXIS, _INVERT_STEP_PIN(AXIS), 0); \
  1393. } \
  1394. }while(0)
  1395. // Determine if pulses are needed
  1396. #if HAS_X_STEP
  1397. PULSE_PREP(X);
  1398. #endif
  1399. #if HAS_Y_STEP
  1400. PULSE_PREP(Y);
  1401. #endif
  1402. #if HAS_Z_STEP
  1403. PULSE_PREP(Z);
  1404. #endif
  1405. #if EITHER(LIN_ADVANCE, MIXING_EXTRUDER)
  1406. delta_error.e += advance_dividend.e;
  1407. if (delta_error.e >= 0) {
  1408. count_position.e += count_direction.e;
  1409. #if ENABLED(LIN_ADVANCE)
  1410. delta_error.e -= advance_divisor;
  1411. // Don't step E here - But remember the number of steps to perform
  1412. motor_direction(E_AXIS) ? --LA_steps : ++LA_steps;
  1413. #else
  1414. step_needed.e = true;
  1415. #endif
  1416. }
  1417. #elif HAS_E0_STEP
  1418. PULSE_PREP(E);
  1419. #endif
  1420. #if ISR_MULTI_STEPS
  1421. if (firstStep)
  1422. firstStep = false;
  1423. else
  1424. AWAIT_LOW_PULSE();
  1425. #endif
  1426. // Pulse start
  1427. #if HAS_X_STEP
  1428. PULSE_START(X);
  1429. #endif
  1430. #if HAS_Y_STEP
  1431. PULSE_START(Y);
  1432. #endif
  1433. #if HAS_Z_STEP
  1434. PULSE_START(Z);
  1435. #endif
  1436. #if DISABLED(LIN_ADVANCE)
  1437. #if ENABLED(MIXING_EXTRUDER)
  1438. if (step_needed.e) E_STEP_WRITE(mixer.get_next_stepper(), !INVERT_E_STEP_PIN);
  1439. #elif HAS_E0_STEP
  1440. PULSE_START(E);
  1441. #endif
  1442. #endif
  1443. #if ENABLED(I2S_STEPPER_STREAM)
  1444. i2s_push_sample();
  1445. #endif
  1446. // TODO: need to deal with MINIMUM_STEPPER_PULSE over i2s
  1447. #if ISR_MULTI_STEPS
  1448. START_HIGH_PULSE();
  1449. AWAIT_HIGH_PULSE();
  1450. #endif
  1451. // Pulse stop
  1452. #if HAS_X_STEP
  1453. PULSE_STOP(X);
  1454. #endif
  1455. #if HAS_Y_STEP
  1456. PULSE_STOP(Y);
  1457. #endif
  1458. #if HAS_Z_STEP
  1459. PULSE_STOP(Z);
  1460. #endif
  1461. #if DISABLED(LIN_ADVANCE)
  1462. #if ENABLED(MIXING_EXTRUDER)
  1463. if (delta_error.e >= 0) {
  1464. delta_error.e -= advance_divisor;
  1465. E_STEP_WRITE(mixer.get_stepper(), INVERT_E_STEP_PIN);
  1466. }
  1467. #elif HAS_E0_STEP
  1468. PULSE_STOP(E);
  1469. #endif
  1470. #endif
  1471. #if ISR_MULTI_STEPS
  1472. if (events_to_do) START_LOW_PULSE();
  1473. #endif
  1474. } while (--events_to_do);
  1475. }
  1476. // This is the last half of the stepper interrupt: This one processes and
  1477. // properly schedules blocks from the planner. This is executed after creating
  1478. // the step pulses, so it is not time critical, as pulses are already done.
  1479. uint32_t Stepper::block_phase_isr() {
  1480. // If no queued movements, just wait 1ms for the next block
  1481. uint32_t interval = (STEPPER_TIMER_RATE) / 1000UL;
  1482. // If there is a current block
  1483. if (current_block) {
  1484. // If current block is finished, reset pointer
  1485. if (step_events_completed >= step_event_count) {
  1486. #ifdef FILAMENT_RUNOUT_DISTANCE_MM
  1487. runout.block_completed(current_block);
  1488. #endif
  1489. axis_did_move = 0;
  1490. current_block = nullptr;
  1491. planner.discard_current_block();
  1492. }
  1493. else {
  1494. // Step events not completed yet...
  1495. // Are we in acceleration phase ?
  1496. if (step_events_completed <= accelerate_until) { // Calculate new timer value
  1497. #if ENABLED(S_CURVE_ACCELERATION)
  1498. // Get the next speed to use (Jerk limited!)
  1499. uint32_t acc_step_rate =
  1500. acceleration_time < current_block->acceleration_time
  1501. ? _eval_bezier_curve(acceleration_time)
  1502. : current_block->cruise_rate;
  1503. #else
  1504. acc_step_rate = STEP_MULTIPLY(acceleration_time, current_block->acceleration_rate) + current_block->initial_rate;
  1505. NOMORE(acc_step_rate, current_block->nominal_rate);
  1506. #endif
  1507. // acc_step_rate is in steps/second
  1508. // step_rate to timer interval and steps per stepper isr
  1509. interval = calc_timer_interval(acc_step_rate, &steps_per_isr);
  1510. acceleration_time += interval;
  1511. #if ENABLED(LIN_ADVANCE)
  1512. // Fire ISR if final adv_rate is reached
  1513. if (LA_steps && (!LA_use_advance_lead || LA_isr_rate != current_block->advance_speed))
  1514. initiateLA();
  1515. #endif
  1516. }
  1517. // Are we in Deceleration phase ?
  1518. else if (step_events_completed > decelerate_after) {
  1519. uint32_t step_rate;
  1520. #if ENABLED(S_CURVE_ACCELERATION)
  1521. // If this is the 1st time we process the 2nd half of the trapezoid...
  1522. if (!bezier_2nd_half) {
  1523. // Initialize the Bézier speed curve
  1524. _calc_bezier_curve_coeffs(current_block->cruise_rate, current_block->final_rate, current_block->deceleration_time_inverse);
  1525. bezier_2nd_half = true;
  1526. // The first point starts at cruise rate. Just save evaluation of the Bézier curve
  1527. step_rate = current_block->cruise_rate;
  1528. }
  1529. else {
  1530. // Calculate the next speed to use
  1531. step_rate = deceleration_time < current_block->deceleration_time
  1532. ? _eval_bezier_curve(deceleration_time)
  1533. : current_block->final_rate;
  1534. }
  1535. #else
  1536. // Using the old trapezoidal control
  1537. step_rate = STEP_MULTIPLY(deceleration_time, current_block->acceleration_rate);
  1538. if (step_rate < acc_step_rate) { // Still decelerating?
  1539. step_rate = acc_step_rate - step_rate;
  1540. NOLESS(step_rate, current_block->final_rate);
  1541. }
  1542. else
  1543. step_rate = current_block->final_rate;
  1544. #endif
  1545. // step_rate is in steps/second
  1546. // step_rate to timer interval and steps per stepper isr
  1547. interval = calc_timer_interval(step_rate, &steps_per_isr);
  1548. deceleration_time += interval;
  1549. #if ENABLED(LIN_ADVANCE)
  1550. if (LA_use_advance_lead) {
  1551. // Wake up eISR on first deceleration loop and fire ISR if final adv_rate is reached
  1552. if (step_events_completed <= decelerate_after + steps_per_isr || (LA_steps && LA_isr_rate != current_block->advance_speed)) {
  1553. initiateLA();
  1554. LA_isr_rate = current_block->advance_speed;
  1555. }
  1556. }
  1557. else if (LA_steps) initiateLA();
  1558. #endif
  1559. }
  1560. // We must be in cruise phase otherwise
  1561. else {
  1562. #if ENABLED(LIN_ADVANCE)
  1563. // If there are any esteps, fire the next advance_isr "now"
  1564. if (LA_steps && LA_isr_rate != current_block->advance_speed) initiateLA();
  1565. #endif
  1566. // Calculate the ticks_nominal for this nominal speed, if not done yet
  1567. if (ticks_nominal < 0) {
  1568. // step_rate to timer interval and loops for the nominal speed
  1569. ticks_nominal = calc_timer_interval(current_block->nominal_rate, &steps_per_isr);
  1570. }
  1571. // The timer interval is just the nominal value for the nominal speed
  1572. interval = ticks_nominal;
  1573. }
  1574. }
  1575. }
  1576. // If there is no current block at this point, attempt to pop one from the buffer
  1577. // and prepare its movement
  1578. if (!current_block) {
  1579. // Anything in the buffer?
  1580. if ((current_block = planner.get_current_block())) {
  1581. // Sync block? Sync the stepper counts and return
  1582. while (TEST(current_block->flag, BLOCK_BIT_SYNC_POSITION)) {
  1583. _set_position(current_block->position);
  1584. planner.discard_current_block();
  1585. // Try to get a new block
  1586. if (!(current_block = planner.get_current_block()))
  1587. return interval; // No more queued movements!
  1588. }
  1589. #if HAS_CUTTER
  1590. cutter.apply_power(current_block->cutter_power);
  1591. #endif
  1592. #if ENABLED(POWER_LOSS_RECOVERY)
  1593. recovery.info.sdpos = current_block->sdpos;
  1594. #endif
  1595. // Flag all moving axes for proper endstop handling
  1596. #if IS_CORE
  1597. // Define conditions for checking endstops
  1598. #define S_(N) current_block->steps[CORE_AXIS_##N]
  1599. #define D_(N) TEST(current_block->direction_bits, CORE_AXIS_##N)
  1600. #endif
  1601. #if CORE_IS_XY || CORE_IS_XZ
  1602. /**
  1603. * Head direction in -X axis for CoreXY and CoreXZ bots.
  1604. *
  1605. * If steps differ, both axes are moving.
  1606. * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Y or Z, handled below)
  1607. * If DeltaA == DeltaB, the movement is only in the 1st axis (X)
  1608. */
  1609. #if EITHER(COREXY, COREXZ)
  1610. #define X_CMP ==
  1611. #else
  1612. #define X_CMP !=
  1613. #endif
  1614. #define X_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) X_CMP D_(2)) )
  1615. #else
  1616. #define X_MOVE_TEST !!current_block->steps.a
  1617. #endif
  1618. #if CORE_IS_XY || CORE_IS_YZ
  1619. /**
  1620. * Head direction in -Y axis for CoreXY / CoreYZ bots.
  1621. *
  1622. * If steps differ, both axes are moving
  1623. * If DeltaA == DeltaB, the movement is only in the 1st axis (X or Y)
  1624. * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Y or Z)
  1625. */
  1626. #if EITHER(COREYX, COREYZ)
  1627. #define Y_CMP ==
  1628. #else
  1629. #define Y_CMP !=
  1630. #endif
  1631. #define Y_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) Y_CMP D_(2)) )
  1632. #else
  1633. #define Y_MOVE_TEST !!current_block->steps.b
  1634. #endif
  1635. #if CORE_IS_XZ || CORE_IS_YZ
  1636. /**
  1637. * Head direction in -Z axis for CoreXZ or CoreYZ bots.
  1638. *
  1639. * If steps differ, both axes are moving
  1640. * If DeltaA == DeltaB, the movement is only in the 1st axis (X or Y, already handled above)
  1641. * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Z)
  1642. */
  1643. #if EITHER(COREZX, COREZY)
  1644. #define Z_CMP ==
  1645. #else
  1646. #define Z_CMP !=
  1647. #endif
  1648. #define Z_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) Z_CMP D_(2)) )
  1649. #else
  1650. #define Z_MOVE_TEST !!current_block->steps.c
  1651. #endif
  1652. uint8_t axis_bits = 0;
  1653. if (X_MOVE_TEST) SBI(axis_bits, A_AXIS);
  1654. if (Y_MOVE_TEST) SBI(axis_bits, B_AXIS);
  1655. if (Z_MOVE_TEST) SBI(axis_bits, C_AXIS);
  1656. //if (!!current_block->steps.e) SBI(axis_bits, E_AXIS);
  1657. //if (!!current_block->steps.a) SBI(axis_bits, X_HEAD);
  1658. //if (!!current_block->steps.b) SBI(axis_bits, Y_HEAD);
  1659. //if (!!current_block->steps.c) SBI(axis_bits, Z_HEAD);
  1660. axis_did_move = axis_bits;
  1661. // No acceleration / deceleration time elapsed so far
  1662. acceleration_time = deceleration_time = 0;
  1663. uint8_t oversampling = 0; // Assume no axis smoothing (via oversampling)
  1664. #if ENABLED(ADAPTIVE_STEP_SMOOTHING)
  1665. // Decide if axis smoothing is possible
  1666. uint32_t max_rate = current_block->nominal_rate; // Get the maximum rate (maximum event speed)
  1667. while (max_rate < MIN_STEP_ISR_FREQUENCY) { // As long as more ISRs are possible...
  1668. max_rate <<= 1; // Try to double the rate
  1669. if (max_rate >= MAX_STEP_ISR_FREQUENCY_1X) break; // Don't exceed the estimated ISR limit
  1670. ++oversampling; // Increase the oversampling (used for left-shift)
  1671. }
  1672. oversampling_factor = oversampling; // For all timer interval calculations
  1673. #endif
  1674. // Based on the oversampling factor, do the calculations
  1675. step_event_count = current_block->step_event_count << oversampling;
  1676. // Initialize Bresenham delta errors to 1/2
  1677. delta_error = -int32_t(step_event_count);
  1678. // Calculate Bresenham dividends and divisors
  1679. advance_dividend = current_block->steps << 1;
  1680. advance_divisor = step_event_count << 1;
  1681. // No step events completed so far
  1682. step_events_completed = 0;
  1683. // Compute the acceleration and deceleration points
  1684. accelerate_until = current_block->accelerate_until << oversampling;
  1685. decelerate_after = current_block->decelerate_after << oversampling;
  1686. #if ENABLED(MIXING_EXTRUDER)
  1687. MIXER_STEPPER_SETUP();
  1688. #endif
  1689. #if EXTRUDERS > 1
  1690. stepper_extruder = current_block->extruder;
  1691. #endif
  1692. // Initialize the trapezoid generator from the current block.
  1693. #if ENABLED(LIN_ADVANCE)
  1694. #if DISABLED(MIXING_EXTRUDER) && E_STEPPERS > 1
  1695. // If the now active extruder wasn't in use during the last move, its pressure is most likely gone.
  1696. if (stepper_extruder != last_moved_extruder) LA_current_adv_steps = 0;
  1697. #endif
  1698. if ((LA_use_advance_lead = current_block->use_advance_lead)) {
  1699. LA_final_adv_steps = current_block->final_adv_steps;
  1700. LA_max_adv_steps = current_block->max_adv_steps;
  1701. initiateLA(); // Start the ISR
  1702. LA_isr_rate = current_block->advance_speed;
  1703. }
  1704. else LA_isr_rate = LA_ADV_NEVER;
  1705. #endif
  1706. if (
  1707. #if HAS_L64XX
  1708. true // Always set direction for L64xx (This also enables the chips)
  1709. #else
  1710. current_block->direction_bits != last_direction_bits
  1711. #if DISABLED(MIXING_EXTRUDER)
  1712. || stepper_extruder != last_moved_extruder
  1713. #endif
  1714. #endif
  1715. ) {
  1716. last_direction_bits = current_block->direction_bits;
  1717. #if EXTRUDERS > 1
  1718. last_moved_extruder = stepper_extruder;
  1719. #endif
  1720. #if HAS_L64XX
  1721. L64XX_OK_to_power_up = true;
  1722. #endif
  1723. set_directions();
  1724. }
  1725. // At this point, we must ensure the movement about to execute isn't
  1726. // trying to force the head against a limit switch. If using interrupt-
  1727. // driven change detection, and already against a limit then no call to
  1728. // the endstop_triggered method will be done and the movement will be
  1729. // done against the endstop. So, check the limits here: If the movement
  1730. // is against the limits, the block will be marked as to be killed, and
  1731. // on the next call to this ISR, will be discarded.
  1732. endstops.update();
  1733. #if ENABLED(Z_LATE_ENABLE)
  1734. // If delayed Z enable, enable it now. This option will severely interfere with
  1735. // timing between pulses when chaining motion between blocks, and it could lead
  1736. // to lost steps in both X and Y axis, so avoid using it unless strictly necessary!!
  1737. if (current_block->steps.z) ENABLE_AXIS_Z();
  1738. #endif
  1739. // Mark the time_nominal as not calculated yet
  1740. ticks_nominal = -1;
  1741. #if DISABLED(S_CURVE_ACCELERATION)
  1742. // Set as deceleration point the initial rate of the block
  1743. acc_step_rate = current_block->initial_rate;
  1744. #endif
  1745. #if ENABLED(S_CURVE_ACCELERATION)
  1746. // Initialize the Bézier speed curve
  1747. _calc_bezier_curve_coeffs(current_block->initial_rate, current_block->cruise_rate, current_block->acceleration_time_inverse);
  1748. // We haven't started the 2nd half of the trapezoid
  1749. bezier_2nd_half = false;
  1750. #endif
  1751. // Calculate the initial timer interval
  1752. interval = calc_timer_interval(current_block->initial_rate, &steps_per_isr);
  1753. }
  1754. }
  1755. // Return the interval to wait
  1756. return interval;
  1757. }
  1758. #if ENABLED(LIN_ADVANCE)
  1759. // Timer interrupt for E. LA_steps is set in the main routine
  1760. uint32_t Stepper::advance_isr() {
  1761. uint32_t interval;
  1762. if (LA_use_advance_lead) {
  1763. if (step_events_completed > decelerate_after && LA_current_adv_steps > LA_final_adv_steps) {
  1764. LA_steps--;
  1765. LA_current_adv_steps--;
  1766. interval = LA_isr_rate;
  1767. }
  1768. else if (step_events_completed < decelerate_after && LA_current_adv_steps < LA_max_adv_steps) {
  1769. //step_events_completed <= (uint32_t)accelerate_until) {
  1770. LA_steps++;
  1771. LA_current_adv_steps++;
  1772. interval = LA_isr_rate;
  1773. }
  1774. else
  1775. interval = LA_isr_rate = LA_ADV_NEVER;
  1776. }
  1777. else
  1778. interval = LA_ADV_NEVER;
  1779. DIR_WAIT_BEFORE();
  1780. #if ENABLED(MIXING_EXTRUDER)
  1781. // We don't know which steppers will be stepped because LA loop follows,
  1782. // with potentially multiple steps. Set all.
  1783. if (LA_steps >= 0)
  1784. MIXER_STEPPER_LOOP(j) NORM_E_DIR(j);
  1785. else
  1786. MIXER_STEPPER_LOOP(j) REV_E_DIR(j);
  1787. #else
  1788. if (LA_steps >= 0)
  1789. NORM_E_DIR(stepper_extruder);
  1790. else
  1791. REV_E_DIR(stepper_extruder);
  1792. #endif
  1793. DIR_WAIT_AFTER();
  1794. //const hal_timer_t added_step_ticks = hal_timer_t(ADDED_STEP_TICKS);
  1795. // Step E stepper if we have steps
  1796. #if ISR_MULTI_STEPS
  1797. bool firstStep = true;
  1798. USING_TIMED_PULSE();
  1799. #endif
  1800. while (LA_steps) {
  1801. #if ISR_MULTI_STEPS
  1802. if (firstStep)
  1803. firstStep = false;
  1804. else
  1805. AWAIT_LOW_PULSE();
  1806. #endif
  1807. // Set the STEP pulse ON
  1808. #if ENABLED(MIXING_EXTRUDER)
  1809. E_STEP_WRITE(mixer.get_next_stepper(), !INVERT_E_STEP_PIN);
  1810. #else
  1811. E_STEP_WRITE(stepper_extruder, !INVERT_E_STEP_PIN);
  1812. #endif
  1813. // Enforce a minimum duration for STEP pulse ON
  1814. #if ISR_PULSE_CONTROL
  1815. START_HIGH_PULSE();
  1816. #endif
  1817. LA_steps < 0 ? ++LA_steps : --LA_steps;
  1818. #if ISR_PULSE_CONTROL
  1819. AWAIT_HIGH_PULSE();
  1820. #endif
  1821. // Set the STEP pulse OFF
  1822. #if ENABLED(MIXING_EXTRUDER)
  1823. E_STEP_WRITE(mixer.get_stepper(), INVERT_E_STEP_PIN);
  1824. #else
  1825. E_STEP_WRITE(stepper_extruder, INVERT_E_STEP_PIN);
  1826. #endif
  1827. // For minimum pulse time wait before looping
  1828. // Just wait for the requested pulse duration
  1829. #if ISR_PULSE_CONTROL
  1830. if (LA_steps) START_LOW_PULSE();
  1831. #endif
  1832. } // LA_steps
  1833. return interval;
  1834. }
  1835. #endif // LIN_ADVANCE
  1836. #if ENABLED(INTEGRATED_BABYSTEPPING)
  1837. // Timer interrupt for baby-stepping
  1838. uint32_t Stepper::babystepping_isr() {
  1839. babystep.task();
  1840. return babystep.has_steps() ? BABYSTEP_TICKS : BABYSTEP_NEVER;
  1841. }
  1842. #endif
  1843. // Check if the given block is busy or not - Must not be called from ISR contexts
  1844. // The current_block could change in the middle of the read by an Stepper ISR, so
  1845. // we must explicitly prevent that!
  1846. bool Stepper::is_block_busy(const block_t* const block) {
  1847. #ifdef __AVR__
  1848. // A SW memory barrier, to ensure GCC does not overoptimize loops
  1849. #define sw_barrier() asm volatile("": : :"memory");
  1850. // Keep reading until 2 consecutive reads return the same value,
  1851. // meaning there was no update in-between caused by an interrupt.
  1852. // This works because stepper ISRs happen at a slower rate than
  1853. // successive reads of a variable, so 2 consecutive reads with
  1854. // the same value means no interrupt updated it.
  1855. block_t* vold, *vnew = current_block;
  1856. sw_barrier();
  1857. do {
  1858. vold = vnew;
  1859. vnew = current_block;
  1860. sw_barrier();
  1861. } while (vold != vnew);
  1862. #else
  1863. block_t *vnew = current_block;
  1864. #endif
  1865. // Return if the block is busy or not
  1866. return block == vnew;
  1867. }
  1868. void Stepper::init() {
  1869. #if MB(ALLIGATOR)
  1870. const float motor_current[] = MOTOR_CURRENT;
  1871. unsigned int digipot_motor = 0;
  1872. for (uint8_t i = 0; i < 3 + EXTRUDERS; i++) {
  1873. digipot_motor = 255 * (motor_current[i] / 2.5);
  1874. dac084s085::setValue(i, digipot_motor);
  1875. }
  1876. #endif
  1877. // Init Microstepping Pins
  1878. #if HAS_MICROSTEPS
  1879. microstep_init();
  1880. #endif
  1881. // Init Dir Pins
  1882. #if HAS_X_DIR
  1883. X_DIR_INIT();
  1884. #endif
  1885. #if HAS_X2_DIR
  1886. X2_DIR_INIT();
  1887. #endif
  1888. #if HAS_Y_DIR
  1889. Y_DIR_INIT();
  1890. #if ENABLED(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_DIR
  1891. Y2_DIR_INIT();
  1892. #endif
  1893. #endif
  1894. #if HAS_Z_DIR
  1895. Z_DIR_INIT();
  1896. #if NUM_Z_STEPPER_DRIVERS >= 2 && HAS_Z2_DIR
  1897. Z2_DIR_INIT();
  1898. #endif
  1899. #if NUM_Z_STEPPER_DRIVERS >= 3 && HAS_Z3_DIR
  1900. Z3_DIR_INIT();
  1901. #endif
  1902. #if NUM_Z_STEPPER_DRIVERS >= 4 && HAS_Z4_DIR
  1903. Z4_DIR_INIT();
  1904. #endif
  1905. #endif
  1906. #if HAS_E0_DIR
  1907. E0_DIR_INIT();
  1908. #endif
  1909. #if HAS_E1_DIR
  1910. E1_DIR_INIT();
  1911. #endif
  1912. #if HAS_E2_DIR
  1913. E2_DIR_INIT();
  1914. #endif
  1915. #if HAS_E3_DIR
  1916. E3_DIR_INIT();
  1917. #endif
  1918. #if HAS_E4_DIR
  1919. E4_DIR_INIT();
  1920. #endif
  1921. #if HAS_E5_DIR
  1922. E5_DIR_INIT();
  1923. #endif
  1924. #if HAS_E6_DIR
  1925. E6_DIR_INIT();
  1926. #endif
  1927. #if HAS_E7_DIR
  1928. E7_DIR_INIT();
  1929. #endif
  1930. // Init Enable Pins - steppers default to disabled.
  1931. #if HAS_X_ENABLE
  1932. X_ENABLE_INIT();
  1933. if (!X_ENABLE_ON) X_ENABLE_WRITE(HIGH);
  1934. #if EITHER(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS) && HAS_X2_ENABLE
  1935. X2_ENABLE_INIT();
  1936. if (!X_ENABLE_ON) X2_ENABLE_WRITE(HIGH);
  1937. #endif
  1938. #endif
  1939. #if HAS_Y_ENABLE
  1940. Y_ENABLE_INIT();
  1941. if (!Y_ENABLE_ON) Y_ENABLE_WRITE(HIGH);
  1942. #if ENABLED(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_ENABLE
  1943. Y2_ENABLE_INIT();
  1944. if (!Y_ENABLE_ON) Y2_ENABLE_WRITE(HIGH);
  1945. #endif
  1946. #endif
  1947. #if HAS_Z_ENABLE
  1948. Z_ENABLE_INIT();
  1949. if (!Z_ENABLE_ON) Z_ENABLE_WRITE(HIGH);
  1950. #if NUM_Z_STEPPER_DRIVERS >= 2 && HAS_Z2_ENABLE
  1951. Z2_ENABLE_INIT();
  1952. if (!Z_ENABLE_ON) Z2_ENABLE_WRITE(HIGH);
  1953. #endif
  1954. #if NUM_Z_STEPPER_DRIVERS >= 3 && HAS_Z3_ENABLE
  1955. Z3_ENABLE_INIT();
  1956. if (!Z_ENABLE_ON) Z3_ENABLE_WRITE(HIGH);
  1957. #endif
  1958. #if NUM_Z_STEPPER_DRIVERS >= 4 && HAS_Z4_ENABLE
  1959. Z4_ENABLE_INIT();
  1960. if (!Z_ENABLE_ON) Z4_ENABLE_WRITE(HIGH);
  1961. #endif
  1962. #endif
  1963. #if HAS_E0_ENABLE
  1964. E0_ENABLE_INIT();
  1965. if (!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH);
  1966. #endif
  1967. #if HAS_E1_ENABLE
  1968. E1_ENABLE_INIT();
  1969. if (!E_ENABLE_ON) E1_ENABLE_WRITE(HIGH);
  1970. #endif
  1971. #if HAS_E2_ENABLE
  1972. E2_ENABLE_INIT();
  1973. if (!E_ENABLE_ON) E2_ENABLE_WRITE(HIGH);
  1974. #endif
  1975. #if HAS_E3_ENABLE
  1976. E3_ENABLE_INIT();
  1977. if (!E_ENABLE_ON) E3_ENABLE_WRITE(HIGH);
  1978. #endif
  1979. #if HAS_E4_ENABLE
  1980. E4_ENABLE_INIT();
  1981. if (!E_ENABLE_ON) E4_ENABLE_WRITE(HIGH);
  1982. #endif
  1983. #if HAS_E5_ENABLE
  1984. E5_ENABLE_INIT();
  1985. if (!E_ENABLE_ON) E5_ENABLE_WRITE(HIGH);
  1986. #endif
  1987. #if HAS_E6_ENABLE
  1988. E6_ENABLE_INIT();
  1989. if (!E_ENABLE_ON) E6_ENABLE_WRITE(HIGH);
  1990. #endif
  1991. #if HAS_E7_ENABLE
  1992. E7_ENABLE_INIT();
  1993. if (!E_ENABLE_ON) E7_ENABLE_WRITE(HIGH);
  1994. #endif
  1995. #define _STEP_INIT(AXIS) AXIS ##_STEP_INIT()
  1996. #define _WRITE_STEP(AXIS, HIGHLOW) AXIS ##_STEP_WRITE(HIGHLOW)
  1997. #define _DISABLE_AXIS(AXIS) DISABLE_AXIS_## AXIS()
  1998. #define AXIS_INIT(AXIS, PIN) \
  1999. _STEP_INIT(AXIS); \
  2000. _WRITE_STEP(AXIS, _INVERT_STEP_PIN(PIN)); \
  2001. _DISABLE_AXIS(AXIS)
  2002. #define E_AXIS_INIT(NUM) AXIS_INIT(E## NUM, E)
  2003. // Init Step Pins
  2004. #if HAS_X_STEP
  2005. #if EITHER(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE)
  2006. X2_STEP_INIT();
  2007. X2_STEP_WRITE(INVERT_X_STEP_PIN);
  2008. #endif
  2009. AXIS_INIT(X, X);
  2010. #endif
  2011. #if HAS_Y_STEP
  2012. #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
  2013. Y2_STEP_INIT();
  2014. Y2_STEP_WRITE(INVERT_Y_STEP_PIN);
  2015. #endif
  2016. AXIS_INIT(Y, Y);
  2017. #endif
  2018. #if HAS_Z_STEP
  2019. #if NUM_Z_STEPPER_DRIVERS >= 2
  2020. Z2_STEP_INIT();
  2021. Z2_STEP_WRITE(INVERT_Z_STEP_PIN);
  2022. #endif
  2023. #if NUM_Z_STEPPER_DRIVERS >= 3
  2024. Z3_STEP_INIT();
  2025. Z3_STEP_WRITE(INVERT_Z_STEP_PIN);
  2026. #endif
  2027. #if NUM_Z_STEPPER_DRIVERS >= 4
  2028. Z4_STEP_INIT();
  2029. Z4_STEP_WRITE(INVERT_Z_STEP_PIN);
  2030. #endif
  2031. AXIS_INIT(Z, Z);
  2032. #endif
  2033. #if E_STEPPERS > 0 && HAS_E0_STEP
  2034. E_AXIS_INIT(0);
  2035. #endif
  2036. #if E_STEPPERS > 1 && HAS_E1_STEP
  2037. E_AXIS_INIT(1);
  2038. #endif
  2039. #if E_STEPPERS > 2 && HAS_E2_STEP
  2040. E_AXIS_INIT(2);
  2041. #endif
  2042. #if E_STEPPERS > 3 && HAS_E3_STEP
  2043. E_AXIS_INIT(3);
  2044. #endif
  2045. #if E_STEPPERS > 4 && HAS_E4_STEP
  2046. E_AXIS_INIT(4);
  2047. #endif
  2048. #if E_STEPPERS > 5 && HAS_E5_STEP
  2049. E_AXIS_INIT(5);
  2050. #endif
  2051. #if E_STEPPERS > 6 && HAS_E6_STEP
  2052. E_AXIS_INIT(6);
  2053. #endif
  2054. #if E_STEPPERS > 7 && HAS_E7_STEP
  2055. E_AXIS_INIT(7);
  2056. #endif
  2057. #if DISABLED(I2S_STEPPER_STREAM)
  2058. HAL_timer_start(STEP_TIMER_NUM, 122); // Init Stepper ISR to 122 Hz for quick starting
  2059. wake_up();
  2060. sei();
  2061. #endif
  2062. // Init direction bits for first moves
  2063. last_direction_bits = 0
  2064. | (INVERT_X_DIR ? _BV(X_AXIS) : 0)
  2065. | (INVERT_Y_DIR ? _BV(Y_AXIS) : 0)
  2066. | (INVERT_Z_DIR ? _BV(Z_AXIS) : 0);
  2067. set_directions();
  2068. #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM
  2069. #if HAS_MOTOR_CURRENT_PWM
  2070. initialized = true;
  2071. #endif
  2072. digipot_init();
  2073. #endif
  2074. }
  2075. /**
  2076. * Set the stepper positions directly in steps
  2077. *
  2078. * The input is based on the typical per-axis XYZ steps.
  2079. * For CORE machines XYZ needs to be translated to ABC.
  2080. *
  2081. * This allows get_axis_position_mm to correctly
  2082. * derive the current XYZ position later on.
  2083. */
  2084. void Stepper::_set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e) {
  2085. #if CORE_IS_XY
  2086. // corexy positioning
  2087. // these equations follow the form of the dA and dB equations on http://www.corexy.com/theory.html
  2088. count_position.set(a + b, CORESIGN(a - b), c);
  2089. #elif CORE_IS_XZ
  2090. // corexz planning
  2091. count_position.set(a + c, b, CORESIGN(a - c));
  2092. #elif CORE_IS_YZ
  2093. // coreyz planning
  2094. count_position.set(a, b + c, CORESIGN(b - c));
  2095. #else
  2096. // default non-h-bot planning
  2097. count_position.set(a, b, c);
  2098. #endif
  2099. count_position.e = e;
  2100. }
  2101. /**
  2102. * Get a stepper's position in steps.
  2103. */
  2104. int32_t Stepper::position(const AxisEnum axis) {
  2105. #ifdef __AVR__
  2106. // Protect the access to the position. Only required for AVR, as
  2107. // any 32bit CPU offers atomic access to 32bit variables
  2108. const bool was_enabled = suspend();
  2109. #endif
  2110. const int32_t v = count_position[axis];
  2111. #ifdef __AVR__
  2112. // Reenable Stepper ISR
  2113. if (was_enabled) wake_up();
  2114. #endif
  2115. return v;
  2116. }
  2117. // Set the current position in steps
  2118. void Stepper::set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e) {
  2119. planner.synchronize();
  2120. const bool was_enabled = suspend();
  2121. _set_position(a, b, c, e);
  2122. if (was_enabled) wake_up();
  2123. }
  2124. void Stepper::set_axis_position(const AxisEnum a, const int32_t &v) {
  2125. planner.synchronize();
  2126. #ifdef __AVR__
  2127. // Protect the access to the position. Only required for AVR, as
  2128. // any 32bit CPU offers atomic access to 32bit variables
  2129. const bool was_enabled = suspend();
  2130. #endif
  2131. count_position[a] = v;
  2132. #ifdef __AVR__
  2133. // Reenable Stepper ISR
  2134. if (was_enabled) wake_up();
  2135. #endif
  2136. }
  2137. // Signal endstops were triggered - This function can be called from
  2138. // an ISR context (Temperature, Stepper or limits ISR), so we must
  2139. // be very careful here. If the interrupt being preempted was the
  2140. // Stepper ISR (this CAN happen with the endstop limits ISR) then
  2141. // when the stepper ISR resumes, we must be very sure that the movement
  2142. // is properly canceled
  2143. void Stepper::endstop_triggered(const AxisEnum axis) {
  2144. const bool was_enabled = suspend();
  2145. endstops_trigsteps[axis] = (
  2146. #if IS_CORE
  2147. (axis == CORE_AXIS_2
  2148. ? CORESIGN(count_position[CORE_AXIS_1] - count_position[CORE_AXIS_2])
  2149. : count_position[CORE_AXIS_1] + count_position[CORE_AXIS_2]
  2150. ) * double(0.5)
  2151. #else // !IS_CORE
  2152. count_position[axis]
  2153. #endif
  2154. );
  2155. // Discard the rest of the move if there is a current block
  2156. quick_stop();
  2157. if (was_enabled) wake_up();
  2158. }
  2159. int32_t Stepper::triggered_position(const AxisEnum axis) {
  2160. #ifdef __AVR__
  2161. // Protect the access to the position. Only required for AVR, as
  2162. // any 32bit CPU offers atomic access to 32bit variables
  2163. const bool was_enabled = suspend();
  2164. #endif
  2165. const int32_t v = endstops_trigsteps[axis];
  2166. #ifdef __AVR__
  2167. // Reenable Stepper ISR
  2168. if (was_enabled) wake_up();
  2169. #endif
  2170. return v;
  2171. }
  2172. void Stepper::report_positions() {
  2173. #ifdef __AVR__
  2174. // Protect the access to the position.
  2175. const bool was_enabled = suspend();
  2176. #endif
  2177. const xyz_long_t pos = count_position;
  2178. #ifdef __AVR__
  2179. if (was_enabled) wake_up();
  2180. #endif
  2181. #if CORE_IS_XY || CORE_IS_XZ || ENABLED(DELTA) || IS_SCARA
  2182. SERIAL_ECHOPAIR(MSG_COUNT_A, pos.x, " B:", pos.y);
  2183. #else
  2184. SERIAL_ECHOPAIR(MSG_COUNT_X, pos.x, " Y:", pos.y);
  2185. #endif
  2186. #if CORE_IS_XZ || CORE_IS_YZ || ENABLED(DELTA)
  2187. SERIAL_ECHOLNPAIR(" C:", pos.z);
  2188. #else
  2189. SERIAL_ECHOLNPAIR(" Z:", pos.z);
  2190. #endif
  2191. }
  2192. #if ENABLED(BABYSTEPPING)
  2193. #define _ENABLE_AXIS(AXIS) ENABLE_AXIS_## AXIS()
  2194. #define _READ_DIR(AXIS) AXIS ##_DIR_READ()
  2195. #define _INVERT_DIR(AXIS) INVERT_## AXIS ##_DIR
  2196. #define _APPLY_DIR(AXIS, INVERT) AXIS ##_APPLY_DIR(INVERT, true)
  2197. #if MINIMUM_STEPPER_PULSE
  2198. #define STEP_PULSE_CYCLES ((MINIMUM_STEPPER_PULSE) * CYCLES_PER_MICROSECOND)
  2199. #else
  2200. #define STEP_PULSE_CYCLES 0
  2201. #endif
  2202. #if ENABLED(DELTA)
  2203. #define CYCLES_EATEN_BABYSTEP (2 * 15)
  2204. #else
  2205. #define CYCLES_EATEN_BABYSTEP 0
  2206. #endif
  2207. #define EXTRA_CYCLES_BABYSTEP (STEP_PULSE_CYCLES - (CYCLES_EATEN_BABYSTEP))
  2208. #if EXTRA_CYCLES_BABYSTEP > 20
  2209. #define _SAVE_START() const hal_timer_t pulse_start = HAL_timer_get_count(PULSE_TIMER_NUM)
  2210. #define _PULSE_WAIT() while (EXTRA_CYCLES_BABYSTEP > (uint32_t)(HAL_timer_get_count(PULSE_TIMER_NUM) - pulse_start) * (PULSE_TIMER_PRESCALE)) { /* nada */ }
  2211. #else
  2212. #define _SAVE_START() NOOP
  2213. #if EXTRA_CYCLES_BABYSTEP > 0
  2214. #define _PULSE_WAIT() DELAY_NS(EXTRA_CYCLES_BABYSTEP * NANOSECONDS_PER_CYCLE)
  2215. #elif ENABLED(DELTA)
  2216. #define _PULSE_WAIT() DELAY_US(2);
  2217. #elif STEP_PULSE_CYCLES > 0
  2218. #define _PULSE_WAIT() NOOP
  2219. #else
  2220. #define _PULSE_WAIT() DELAY_US(4);
  2221. #endif
  2222. #endif
  2223. #if DISABLED(DELTA)
  2224. #define BABYSTEP_AXIS(AXIS, INV, DIR) do{ \
  2225. const uint8_t old_dir = _READ_DIR(AXIS); \
  2226. _ENABLE_AXIS(AXIS); \
  2227. DIR_WAIT_BEFORE(); \
  2228. _APPLY_DIR(AXIS, _INVERT_DIR(AXIS)^DIR^INV); \
  2229. DIR_WAIT_AFTER(); \
  2230. _SAVE_START(); \
  2231. _APPLY_STEP(AXIS, !_INVERT_STEP_PIN(AXIS), true); \
  2232. _PULSE_WAIT(); \
  2233. _APPLY_STEP(AXIS, _INVERT_STEP_PIN(AXIS), true); \
  2234. DIR_WAIT_BEFORE(); \
  2235. _APPLY_DIR(AXIS, old_dir); \
  2236. DIR_WAIT_AFTER(); \
  2237. }while(0)
  2238. #elif IS_CORE
  2239. #define BABYSTEP_CORE(A, B, INV, DIR, ALT) do{ \
  2240. const xy_byte_t old_dir = { _READ_DIR(A), _READ_DIR(B) }; \
  2241. _ENABLE_AXIS(A); _ENABLE_AXIS(B); \
  2242. DIR_WAIT_BEFORE(); \
  2243. _APPLY_DIR(A, _INVERT_DIR(A)^DIR^INV); \
  2244. _APPLY_DIR(B, _INVERT_DIR(B)^DIR^INV^ALT); \
  2245. DIR_WAIT_AFTER(); \
  2246. _SAVE_START(); \
  2247. _APPLY_STEP(A, !_INVERT_STEP_PIN(A), true); \
  2248. _APPLY_STEP(B, !_INVERT_STEP_PIN(B), true); \
  2249. _PULSE_WAIT(); \
  2250. _APPLY_STEP(A, _INVERT_STEP_PIN(A), true); \
  2251. _APPLY_STEP(B, _INVERT_STEP_PIN(B), true); \
  2252. DIR_WAIT_BEFORE(); \
  2253. _APPLY_DIR(A, old_dir.a); _APPLY_DIR(B, old_dir.b); \
  2254. DIR_WAIT_AFTER(); \
  2255. }while(0)
  2256. #endif
  2257. // MUST ONLY BE CALLED BY AN ISR,
  2258. // No other ISR should ever interrupt this!
  2259. void Stepper::do_babystep(const AxisEnum axis, const bool direction) {
  2260. #if DISABLED(INTEGRATED_BABYSTEPPING)
  2261. cli();
  2262. #endif
  2263. switch (axis) {
  2264. #if ENABLED(BABYSTEP_XY)
  2265. case X_AXIS:
  2266. #if CORE_IS_XY
  2267. BABYSTEP_CORE(X, Y, 0, direction, 0);
  2268. #elif CORE_IS_XZ
  2269. BABYSTEP_CORE(X, Z, 0, direction, 0);
  2270. #else
  2271. BABYSTEP_AXIS(X, 0, direction);
  2272. #endif
  2273. break;
  2274. case Y_AXIS:
  2275. #if CORE_IS_XY
  2276. BABYSTEP_CORE(X, Y, 0, direction, (CORESIGN(1)<0));
  2277. #elif CORE_IS_YZ
  2278. BABYSTEP_CORE(Y, Z, 0, direction, (CORESIGN(1)<0));
  2279. #else
  2280. BABYSTEP_AXIS(Y, 0, direction);
  2281. #endif
  2282. break;
  2283. #endif
  2284. case Z_AXIS: {
  2285. #if CORE_IS_XZ
  2286. BABYSTEP_CORE(X, Z, BABYSTEP_INVERT_Z, direction, (CORESIGN(1)<0));
  2287. #elif CORE_IS_YZ
  2288. BABYSTEP_CORE(Y, Z, BABYSTEP_INVERT_Z, direction, (CORESIGN(1)<0));
  2289. #elif DISABLED(DELTA)
  2290. BABYSTEP_AXIS(Z, BABYSTEP_INVERT_Z, direction);
  2291. #else // DELTA
  2292. const bool z_direction = direction ^ BABYSTEP_INVERT_Z;
  2293. ENABLE_AXIS_X();
  2294. ENABLE_AXIS_Y();
  2295. ENABLE_AXIS_Z();
  2296. DIR_WAIT_BEFORE();
  2297. const xyz_byte_t old_dir = { X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ() };
  2298. X_DIR_WRITE(INVERT_X_DIR ^ z_direction);
  2299. Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction);
  2300. Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction);
  2301. DIR_WAIT_AFTER();
  2302. _SAVE_START();
  2303. X_STEP_WRITE(!INVERT_X_STEP_PIN);
  2304. Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
  2305. Z_STEP_WRITE(!INVERT_Z_STEP_PIN);
  2306. _PULSE_WAIT();
  2307. X_STEP_WRITE(INVERT_X_STEP_PIN);
  2308. Y_STEP_WRITE(INVERT_Y_STEP_PIN);
  2309. Z_STEP_WRITE(INVERT_Z_STEP_PIN);
  2310. // Restore direction bits
  2311. DIR_WAIT_BEFORE();
  2312. X_DIR_WRITE(old_dir.x);
  2313. Y_DIR_WRITE(old_dir.y);
  2314. Z_DIR_WRITE(old_dir.z);
  2315. DIR_WAIT_AFTER();
  2316. #endif
  2317. } break;
  2318. default: break;
  2319. }
  2320. #if DISABLED(INTEGRATED_BABYSTEPPING)
  2321. sei();
  2322. #endif
  2323. }
  2324. #endif // BABYSTEPPING
  2325. /**
  2326. * Software-controlled Stepper Motor Current
  2327. */
  2328. #if HAS_DIGIPOTSS
  2329. // From Arduino DigitalPotControl example
  2330. void Stepper::digitalPotWrite(const int16_t address, const int16_t value) {
  2331. WRITE(DIGIPOTSS_PIN, LOW); // Take the SS pin low to select the chip
  2332. SPI.transfer(address); // Send the address and value via SPI
  2333. SPI.transfer(value);
  2334. WRITE(DIGIPOTSS_PIN, HIGH); // Take the SS pin high to de-select the chip
  2335. //delay(10);
  2336. }
  2337. #endif // HAS_DIGIPOTSS
  2338. #if HAS_MOTOR_CURRENT_PWM
  2339. void Stepper::refresh_motor_power() {
  2340. if (!initialized) return;
  2341. LOOP_L_N(i, COUNT(motor_current_setting)) {
  2342. switch (i) {
  2343. #if ANY_PIN(MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y)
  2344. case 0:
  2345. #endif
  2346. #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
  2347. case 1:
  2348. #endif
  2349. #if ANY_PIN(MOTOR_CURRENT_PWM_E, MOTOR_CURRENT_PWM_E0, MOTOR_CURRENT_PWM_E1)
  2350. case 2:
  2351. #endif
  2352. digipot_current(i, motor_current_setting[i]);
  2353. default: break;
  2354. }
  2355. }
  2356. }
  2357. #endif // HAS_MOTOR_CURRENT_PWM
  2358. #if !MB(PRINTRBOARD_G2)
  2359. #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM
  2360. void Stepper::digipot_current(const uint8_t driver, const int16_t current) {
  2361. #if HAS_DIGIPOTSS
  2362. const uint8_t digipot_ch[] = DIGIPOT_CHANNELS;
  2363. digitalPotWrite(digipot_ch[driver], current);
  2364. #elif HAS_MOTOR_CURRENT_PWM
  2365. if (!initialized) return;
  2366. if (WITHIN(driver, 0, COUNT(motor_current_setting) - 1))
  2367. motor_current_setting[driver] = current; // update motor_current_setting
  2368. #define _WRITE_CURRENT_PWM(P) analogWrite(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE))
  2369. switch (driver) {
  2370. case 0:
  2371. #if PIN_EXISTS(MOTOR_CURRENT_PWM_X)
  2372. _WRITE_CURRENT_PWM(X);
  2373. #endif
  2374. #if PIN_EXISTS(MOTOR_CURRENT_PWM_Y)
  2375. _WRITE_CURRENT_PWM(Y);
  2376. #endif
  2377. #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
  2378. _WRITE_CURRENT_PWM(XY);
  2379. #endif
  2380. break;
  2381. case 1:
  2382. #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
  2383. _WRITE_CURRENT_PWM(Z);
  2384. #endif
  2385. break;
  2386. case 2:
  2387. #if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
  2388. _WRITE_CURRENT_PWM(E);
  2389. #endif
  2390. #if PIN_EXISTS(MOTOR_CURRENT_PWM_E0)
  2391. _WRITE_CURRENT_PWM(E0);
  2392. #endif
  2393. #if PIN_EXISTS(MOTOR_CURRENT_PWM_E1)
  2394. _WRITE_CURRENT_PWM(E1);
  2395. #endif
  2396. break;
  2397. }
  2398. #endif
  2399. }
  2400. void Stepper::digipot_init() {
  2401. #if HAS_DIGIPOTSS
  2402. static const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT;
  2403. SPI.begin();
  2404. SET_OUTPUT(DIGIPOTSS_PIN);
  2405. for (uint8_t i = 0; i < COUNT(digipot_motor_current); i++) {
  2406. //digitalPotWrite(digipot_ch[i], digipot_motor_current[i]);
  2407. digipot_current(i, digipot_motor_current[i]);
  2408. }
  2409. #elif HAS_MOTOR_CURRENT_PWM
  2410. #if PIN_EXISTS(MOTOR_CURRENT_PWM_X)
  2411. SET_PWM(MOTOR_CURRENT_PWM_X_PIN);
  2412. #endif
  2413. #if PIN_EXISTS(MOTOR_CURRENT_PWM_Y)
  2414. SET_PWM(MOTOR_CURRENT_PWM_Y_PIN);
  2415. #endif
  2416. #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
  2417. SET_PWM(MOTOR_CURRENT_PWM_XY_PIN);
  2418. #endif
  2419. #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
  2420. SET_PWM(MOTOR_CURRENT_PWM_Z_PIN);
  2421. #endif
  2422. #if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
  2423. SET_PWM(MOTOR_CURRENT_PWM_E_PIN);
  2424. #endif
  2425. #if PIN_EXISTS(MOTOR_CURRENT_PWM_E0)
  2426. SET_PWM(MOTOR_CURRENT_PWM_E0_PIN);
  2427. #endif
  2428. #if PIN_EXISTS(MOTOR_CURRENT_PWM_E1)
  2429. SET_PWM(MOTOR_CURRENT_PWM_E1_PIN);
  2430. #endif
  2431. refresh_motor_power();
  2432. // Set Timer5 to 31khz so the PWM of the motor power is as constant as possible. (removes a buzzing noise)
  2433. #ifdef __AVR__
  2434. SET_CS5(PRESCALER_1);
  2435. #endif
  2436. #endif
  2437. }
  2438. #endif
  2439. #else // PRINTRBOARD_G2
  2440. #include HAL_PATH(../HAL, fastio/G2_PWM.h)
  2441. #endif
  2442. #if HAS_MICROSTEPS
  2443. /**
  2444. * Software-controlled Microstepping
  2445. */
  2446. void Stepper::microstep_init() {
  2447. #if HAS_X_MICROSTEPS
  2448. SET_OUTPUT(X_MS1_PIN);
  2449. SET_OUTPUT(X_MS2_PIN);
  2450. #if PIN_EXISTS(X_MS3)
  2451. SET_OUTPUT(X_MS3_PIN);
  2452. #endif
  2453. #endif
  2454. #if HAS_X2_MICROSTEPS
  2455. SET_OUTPUT(X2_MS1_PIN);
  2456. SET_OUTPUT(X2_MS2_PIN);
  2457. #if PIN_EXISTS(X2_MS3)
  2458. SET_OUTPUT(X2_MS3_PIN);
  2459. #endif
  2460. #endif
  2461. #if HAS_Y_MICROSTEPS
  2462. SET_OUTPUT(Y_MS1_PIN);
  2463. SET_OUTPUT(Y_MS2_PIN);
  2464. #if PIN_EXISTS(Y_MS3)
  2465. SET_OUTPUT(Y_MS3_PIN);
  2466. #endif
  2467. #endif
  2468. #if HAS_Y2_MICROSTEPS
  2469. SET_OUTPUT(Y2_MS1_PIN);
  2470. SET_OUTPUT(Y2_MS2_PIN);
  2471. #if PIN_EXISTS(Y2_MS3)
  2472. SET_OUTPUT(Y2_MS3_PIN);
  2473. #endif
  2474. #endif
  2475. #if HAS_Z_MICROSTEPS
  2476. SET_OUTPUT(Z_MS1_PIN);
  2477. SET_OUTPUT(Z_MS2_PIN);
  2478. #if PIN_EXISTS(Z_MS3)
  2479. SET_OUTPUT(Z_MS3_PIN);
  2480. #endif
  2481. #endif
  2482. #if HAS_Z2_MICROSTEPS
  2483. SET_OUTPUT(Z2_MS1_PIN);
  2484. SET_OUTPUT(Z2_MS2_PIN);
  2485. #if PIN_EXISTS(Z2_MS3)
  2486. SET_OUTPUT(Z2_MS3_PIN);
  2487. #endif
  2488. #endif
  2489. #if HAS_Z3_MICROSTEPS
  2490. SET_OUTPUT(Z3_MS1_PIN);
  2491. SET_OUTPUT(Z3_MS2_PIN);
  2492. #if PIN_EXISTS(Z3_MS3)
  2493. SET_OUTPUT(Z3_MS3_PIN);
  2494. #endif
  2495. #endif
  2496. #if HAS_Z4_MICROSTEPS
  2497. SET_OUTPUT(Z4_MS1_PIN);
  2498. SET_OUTPUT(Z4_MS2_PIN);
  2499. #if PIN_EXISTS(Z4_MS3)
  2500. SET_OUTPUT(Z4_MS3_PIN);
  2501. #endif
  2502. #endif
  2503. #if HAS_E0_MICROSTEPS
  2504. SET_OUTPUT(E0_MS1_PIN);
  2505. SET_OUTPUT(E0_MS2_PIN);
  2506. #if PIN_EXISTS(E0_MS3)
  2507. SET_OUTPUT(E0_MS3_PIN);
  2508. #endif
  2509. #endif
  2510. #if HAS_E1_MICROSTEPS
  2511. SET_OUTPUT(E1_MS1_PIN);
  2512. SET_OUTPUT(E1_MS2_PIN);
  2513. #if PIN_EXISTS(E1_MS3)
  2514. SET_OUTPUT(E1_MS3_PIN);
  2515. #endif
  2516. #endif
  2517. #if HAS_E2_MICROSTEPS
  2518. SET_OUTPUT(E2_MS1_PIN);
  2519. SET_OUTPUT(E2_MS2_PIN);
  2520. #if PIN_EXISTS(E2_MS3)
  2521. SET_OUTPUT(E2_MS3_PIN);
  2522. #endif
  2523. #endif
  2524. #if HAS_E3_MICROSTEPS
  2525. SET_OUTPUT(E3_MS1_PIN);
  2526. SET_OUTPUT(E3_MS2_PIN);
  2527. #if PIN_EXISTS(E3_MS3)
  2528. SET_OUTPUT(E3_MS3_PIN);
  2529. #endif
  2530. #endif
  2531. #if HAS_E4_MICROSTEPS
  2532. SET_OUTPUT(E4_MS1_PIN);
  2533. SET_OUTPUT(E4_MS2_PIN);
  2534. #if PIN_EXISTS(E4_MS3)
  2535. SET_OUTPUT(E4_MS3_PIN);
  2536. #endif
  2537. #endif
  2538. #if HAS_E5_MICROSTEPS
  2539. SET_OUTPUT(E5_MS1_PIN);
  2540. SET_OUTPUT(E5_MS2_PIN);
  2541. #if PIN_EXISTS(E5_MS3)
  2542. SET_OUTPUT(E5_MS3_PIN);
  2543. #endif
  2544. #endif
  2545. #if HAS_E6_MICROSTEPS
  2546. SET_OUTPUT(E6_MS1_PIN);
  2547. SET_OUTPUT(E6_MS2_PIN);
  2548. #if PIN_EXISTS(E6_MS3)
  2549. SET_OUTPUT(E6_MS3_PIN);
  2550. #endif
  2551. #endif
  2552. #if HAS_E7_MICROSTEPS
  2553. SET_OUTPUT(E7_MS1_PIN);
  2554. SET_OUTPUT(E7_MS2_PIN);
  2555. #if PIN_EXISTS(E7_MS3)
  2556. SET_OUTPUT(E7_MS3_PIN);
  2557. #endif
  2558. #endif
  2559. static const uint8_t microstep_modes[] = MICROSTEP_MODES;
  2560. for (uint16_t i = 0; i < COUNT(microstep_modes); i++)
  2561. microstep_mode(i, microstep_modes[i]);
  2562. }
  2563. void Stepper::microstep_ms(const uint8_t driver, const int8_t ms1, const int8_t ms2, const int8_t ms3) {
  2564. if (ms1 >= 0) switch (driver) {
  2565. #if HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS
  2566. case 0:
  2567. #if HAS_X_MICROSTEPS
  2568. WRITE(X_MS1_PIN, ms1);
  2569. #endif
  2570. #if HAS_X2_MICROSTEPS
  2571. WRITE(X2_MS1_PIN, ms1);
  2572. #endif
  2573. break;
  2574. #endif
  2575. #if HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS
  2576. case 1:
  2577. #if HAS_Y_MICROSTEPS
  2578. WRITE(Y_MS1_PIN, ms1);
  2579. #endif
  2580. #if HAS_Y2_MICROSTEPS
  2581. WRITE(Y2_MS1_PIN, ms1);
  2582. #endif
  2583. break;
  2584. #endif
  2585. #if HAS_SOME_Z_MICROSTEPS
  2586. case 2:
  2587. #if HAS_Z_MICROSTEPS
  2588. WRITE(Z_MS1_PIN, ms1);
  2589. #endif
  2590. #if HAS_Z2_MICROSTEPS
  2591. WRITE(Z2_MS1_PIN, ms1);
  2592. #endif
  2593. #if HAS_Z3_MICROSTEPS
  2594. WRITE(Z3_MS1_PIN, ms1);
  2595. #endif
  2596. #if HAS_Z4_MICROSTEPS
  2597. WRITE(Z4_MS1_PIN, ms1);
  2598. #endif
  2599. break;
  2600. #endif
  2601. #if HAS_E0_MICROSTEPS
  2602. case 3: WRITE(E0_MS1_PIN, ms1); break;
  2603. #endif
  2604. #if HAS_E1_MICROSTEPS
  2605. case 4: WRITE(E1_MS1_PIN, ms1); break;
  2606. #endif
  2607. #if HAS_E2_MICROSTEPS
  2608. case 5: WRITE(E2_MS1_PIN, ms1); break;
  2609. #endif
  2610. #if HAS_E3_MICROSTEPS
  2611. case 6: WRITE(E3_MS1_PIN, ms1); break;
  2612. #endif
  2613. #if HAS_E4_MICROSTEPS
  2614. case 7: WRITE(E4_MS1_PIN, ms1); break;
  2615. #endif
  2616. #if HAS_E5_MICROSTEPS
  2617. case 8: WRITE(E5_MS1_PIN, ms1); break;
  2618. #endif
  2619. #if HAS_E6_MICROSTEPS
  2620. case 9: WRITE(E6_MS1_PIN, ms1); break;
  2621. #endif
  2622. #if HAS_E7_MICROSTEPS
  2623. case 10: WRITE(E7_MS1_PIN, ms1); break;
  2624. #endif
  2625. }
  2626. if (ms2 >= 0) switch (driver) {
  2627. #if HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS
  2628. case 0:
  2629. #if HAS_X_MICROSTEPS
  2630. WRITE(X_MS2_PIN, ms2);
  2631. #endif
  2632. #if HAS_X2_MICROSTEPS
  2633. WRITE(X2_MS2_PIN, ms2);
  2634. #endif
  2635. break;
  2636. #endif
  2637. #if HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS
  2638. case 1:
  2639. #if HAS_Y_MICROSTEPS
  2640. WRITE(Y_MS2_PIN, ms2);
  2641. #endif
  2642. #if HAS_Y2_MICROSTEPS
  2643. WRITE(Y2_MS2_PIN, ms2);
  2644. #endif
  2645. break;
  2646. #endif
  2647. #if HAS_SOME_Z_MICROSTEPS
  2648. case 2:
  2649. #if HAS_Z_MICROSTEPS
  2650. WRITE(Z_MS2_PIN, ms2);
  2651. #endif
  2652. #if HAS_Z2_MICROSTEPS
  2653. WRITE(Z2_MS2_PIN, ms2);
  2654. #endif
  2655. #if HAS_Z3_MICROSTEPS
  2656. WRITE(Z3_MS2_PIN, ms2);
  2657. #endif
  2658. #if HAS_Z4_MICROSTEPS
  2659. WRITE(Z4_MS2_PIN, ms2);
  2660. #endif
  2661. break;
  2662. #endif
  2663. #if HAS_E0_MICROSTEPS
  2664. case 3: WRITE(E0_MS2_PIN, ms2); break;
  2665. #endif
  2666. #if HAS_E1_MICROSTEPS
  2667. case 4: WRITE(E1_MS2_PIN, ms2); break;
  2668. #endif
  2669. #if HAS_E2_MICROSTEPS
  2670. case 5: WRITE(E2_MS2_PIN, ms2); break;
  2671. #endif
  2672. #if HAS_E3_MICROSTEPS
  2673. case 6: WRITE(E3_MS2_PIN, ms2); break;
  2674. #endif
  2675. #if HAS_E4_MICROSTEPS
  2676. case 7: WRITE(E4_MS2_PIN, ms2); break;
  2677. #endif
  2678. #if HAS_E5_MICROSTEPS
  2679. case 8: WRITE(E5_MS2_PIN, ms2); break;
  2680. #endif
  2681. #if HAS_E6_MICROSTEPS
  2682. case 9: WRITE(E6_MS2_PIN, ms2); break;
  2683. #endif
  2684. #if HAS_E7_MICROSTEPS
  2685. case 10: WRITE(E7_MS2_PIN, ms2); break;
  2686. #endif
  2687. }
  2688. if (ms3 >= 0) switch (driver) {
  2689. #if HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS
  2690. case 0:
  2691. #if HAS_X_MICROSTEPS && PIN_EXISTS(X_MS3)
  2692. WRITE(X_MS3_PIN, ms3);
  2693. #endif
  2694. #if HAS_X2_MICROSTEPS && PIN_EXISTS(X2_MS3)
  2695. WRITE(X2_MS3_PIN, ms3);
  2696. #endif
  2697. break;
  2698. #endif
  2699. #if HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS
  2700. case 1:
  2701. #if HAS_Y_MICROSTEPS && PIN_EXISTS(Y_MS3)
  2702. WRITE(Y_MS3_PIN, ms3);
  2703. #endif
  2704. #if HAS_Y2_MICROSTEPS && PIN_EXISTS(Y2_MS3)
  2705. WRITE(Y2_MS3_PIN, ms3);
  2706. #endif
  2707. break;
  2708. #endif
  2709. #if HAS_SOME_Z_MICROSTEPS
  2710. case 2:
  2711. #if HAS_Z_MICROSTEPS && PIN_EXISTS(Z_MS3)
  2712. WRITE(Z_MS3_PIN, ms3);
  2713. #endif
  2714. #if HAS_Z2_MICROSTEPS && PIN_EXISTS(Z2_MS3)
  2715. WRITE(Z2_MS3_PIN, ms3);
  2716. #endif
  2717. #if HAS_Z3_MICROSTEPS && PIN_EXISTS(Z3_MS3)
  2718. WRITE(Z3_MS3_PIN, ms3);
  2719. #endif
  2720. #if HAS_Z4_MICROSTEPS && PIN_EXISTS(Z4_MS3)
  2721. WRITE(Z4_MS3_PIN, ms3);
  2722. #endif
  2723. break;
  2724. #endif
  2725. #if HAS_E0_MICROSTEPS && PIN_EXISTS(E0_MS3)
  2726. case 3: WRITE(E0_MS3_PIN, ms3); break;
  2727. #endif
  2728. #if HAS_E1_MICROSTEPS && PIN_EXISTS(E1_MS3)
  2729. case 4: WRITE(E1_MS3_PIN, ms3); break;
  2730. #endif
  2731. #if HAS_E2_MICROSTEPS && PIN_EXISTS(E2_MS3)
  2732. case 5: WRITE(E2_MS3_PIN, ms3); break;
  2733. #endif
  2734. #if HAS_E3_MICROSTEPS && PIN_EXISTS(E3_MS3)
  2735. case 6: WRITE(E3_MS3_PIN, ms3); break;
  2736. #endif
  2737. #if HAS_E4_MICROSTEPS && PIN_EXISTS(E4_MS3)
  2738. case 7: WRITE(E4_MS3_PIN, ms3); break;
  2739. #endif
  2740. #if HAS_E5_MICROSTEPS && PIN_EXISTS(E5_MS3)
  2741. case 8: WRITE(E5_MS3_PIN, ms3); break;
  2742. #endif
  2743. #if HAS_E6_MICROSTEPS && PIN_EXISTS(E6_MS3)
  2744. case 9: WRITE(E6_MS3_PIN, ms3); break;
  2745. #endif
  2746. #if HAS_E7_MICROSTEPS && PIN_EXISTS(E7_MS3)
  2747. case 10: WRITE(E7_MS3_PIN, ms3); break;
  2748. #endif
  2749. }
  2750. }
  2751. void Stepper::microstep_mode(const uint8_t driver, const uint8_t stepping_mode) {
  2752. switch (stepping_mode) {
  2753. #if HAS_MICROSTEP1
  2754. case 1: microstep_ms(driver, MICROSTEP1); break;
  2755. #endif
  2756. #if HAS_MICROSTEP2
  2757. case 2: microstep_ms(driver, MICROSTEP2); break;
  2758. #endif
  2759. #if HAS_MICROSTEP4
  2760. case 4: microstep_ms(driver, MICROSTEP4); break;
  2761. #endif
  2762. #if HAS_MICROSTEP8
  2763. case 8: microstep_ms(driver, MICROSTEP8); break;
  2764. #endif
  2765. #if HAS_MICROSTEP16
  2766. case 16: microstep_ms(driver, MICROSTEP16); break;
  2767. #endif
  2768. #if HAS_MICROSTEP32
  2769. case 32: microstep_ms(driver, MICROSTEP32); break;
  2770. #endif
  2771. #if HAS_MICROSTEP64
  2772. case 64: microstep_ms(driver, MICROSTEP64); break;
  2773. #endif
  2774. #if HAS_MICROSTEP128
  2775. case 128: microstep_ms(driver, MICROSTEP128); break;
  2776. #endif
  2777. default: SERIAL_ERROR_MSG("Microsteps unavailable"); break;
  2778. }
  2779. }
  2780. void Stepper::microstep_readings() {
  2781. SERIAL_ECHOLNPGM("MS1|MS2|MS3 Pins");
  2782. #if HAS_X_MICROSTEPS
  2783. SERIAL_ECHOPGM("X: ");
  2784. SERIAL_CHAR('0' + READ(X_MS1_PIN), '0' + READ(X_MS2_PIN)
  2785. #if PIN_EXISTS(X_MS3)
  2786. , '0' + READ(X_MS3_PIN)
  2787. #endif
  2788. );
  2789. #endif
  2790. #if HAS_Y_MICROSTEPS
  2791. SERIAL_ECHOPGM("Y: ");
  2792. SERIAL_CHAR('0' + READ(Y_MS1_PIN), '0' + READ(Y_MS2_PIN)
  2793. #if PIN_EXISTS(Y_MS3)
  2794. , '0' + READ(Y_MS3_PIN)
  2795. #endif
  2796. );
  2797. #endif
  2798. #if HAS_Z_MICROSTEPS
  2799. SERIAL_ECHOPGM("Z: ");
  2800. SERIAL_CHAR('0' + READ(Z_MS1_PIN), '0' + READ(Z_MS2_PIN)
  2801. #if PIN_EXISTS(Z_MS3)
  2802. , '0' + READ(Z_MS3_PIN)
  2803. #endif
  2804. );
  2805. #endif
  2806. #if HAS_E0_MICROSTEPS
  2807. SERIAL_ECHOPGM("E0: ");
  2808. SERIAL_CHAR('0' + READ(E0_MS1_PIN), '0' + READ(E0_MS2_PIN)
  2809. #if PIN_EXISTS(E0_MS3)
  2810. , '0' + READ(E0_MS3_PIN)
  2811. #endif
  2812. );
  2813. #endif
  2814. #if HAS_E1_MICROSTEPS
  2815. SERIAL_ECHOPGM("E1: ");
  2816. SERIAL_CHAR('0' + READ(E1_MS1_PIN), '0' + READ(E1_MS2_PIN)
  2817. #if PIN_EXISTS(E1_MS3)
  2818. , '0' + READ(E1_MS3_PIN)
  2819. #endif
  2820. );
  2821. #endif
  2822. #if HAS_E2_MICROSTEPS
  2823. SERIAL_ECHOPGM("E2: ");
  2824. SERIAL_CHAR('0' + READ(E2_MS1_PIN), '0' + READ(E2_MS2_PIN)
  2825. #if PIN_EXISTS(E2_MS3)
  2826. , '0' + READ(E2_MS3_PIN)
  2827. #endif
  2828. );
  2829. #endif
  2830. #if HAS_E3_MICROSTEPS
  2831. SERIAL_ECHOPGM("E3: ");
  2832. SERIAL_CHAR('0' + READ(E3_MS1_PIN), '0' + READ(E3_MS2_PIN)
  2833. #if PIN_EXISTS(E3_MS3)
  2834. , '0' + READ(E3_MS3_PIN)
  2835. #endif
  2836. );
  2837. #endif
  2838. #if HAS_E4_MICROSTEPS
  2839. SERIAL_ECHOPGM("E4: ");
  2840. SERIAL_CHAR('0' + READ(E4_MS1_PIN), '0' + READ(E4_MS2_PIN)
  2841. #if PIN_EXISTS(E4_MS3)
  2842. , '0' + READ(E4_MS3_PIN)
  2843. #endif
  2844. );
  2845. #endif
  2846. #if HAS_E5_MICROSTEPS
  2847. SERIAL_ECHOPGM("E5: ");
  2848. SERIAL_CHAR('0' + READ(E5_MS1_PIN), '0' + READ(E5_MS2_PIN)
  2849. #if PIN_EXISTS(E5_MS3)
  2850. , '0' + READ(E5_MS3_PIN)
  2851. #endif
  2852. );
  2853. #endif
  2854. #if HAS_E6_MICROSTEPS
  2855. SERIAL_ECHOPGM("E6: ");
  2856. SERIAL_CHAR('0' + READ(E6_MS1_PIN), '0' + READ(E6_MS2_PIN)
  2857. #if PIN_EXISTS(E6_MS3)
  2858. , '0' + READ(E6_MS3_PIN)
  2859. #endif
  2860. );
  2861. #endif
  2862. #if HAS_E7_MICROSTEPS
  2863. SERIAL_ECHOPGM("E7: ");
  2864. SERIAL_CHAR('0' + READ(E7_MS1_PIN), '0' + READ(E7_MS2_PIN)
  2865. #if PIN_EXISTS(E7_MS3)
  2866. , '0' + READ(E7_MS3_PIN)
  2867. #endif
  2868. );
  2869. #endif
  2870. }
  2871. #endif // HAS_MICROSTEPS