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

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