Sprinter_2.pde 101 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973197419751976197719781979198019811982198319841985198619871988198919901991199219931994199519961997199819992000200120022003200420052006200720082009201020112012201320142015201620172018201920202021202220232024202520262027202820292030203120322033203420352036203720382039204020412042204320442045204620472048204920502051205220532054205520562057205820592060206120622063206420652066206720682069207020712072207320742075207620772078207920802081208220832084208520862087208820892090209120922093209420952096209720982099210021012102210321042105210621072108210921102111211221132114211521162117211821192120212121222123212421252126212721282129213021312132213321342135213621372138213921402141214221432144214521462147214821492150215121522153215421552156215721582159216021612162216321642165216621672168216921702171217221732174217521762177217821792180218121822183218421852186218721882189219021912192219321942195219621972198219922002201220222032204220522062207220822092210221122122213221422152216221722182219222022212222222322242225222622272228222922302231223222332234223522362237223822392240224122422243224422452246224722482249225022512252225322542255225622572258225922602261226222632264226522662267226822692270227122722273227422752276227722782279228022812282228322842285228622872288228922902291229222932294229522962297229822992300230123022303230423052306230723082309231023112312231323142315231623172318231923202321232223232324232523262327232823292330233123322333233423352336233723382339234023412342234323442345234623472348234923502351235223532354235523562357235823592360236123622363236423652366236723682369237023712372237323742375237623772378237923802381238223832384238523862387238823892390239123922393239423952396239723982399240024012402240324042405240624072408240924102411241224132414241524162417241824192420242124222423242424252426242724282429243024312432243324342435243624372438243924402441244224432444244524462447244824492450245124522453245424552456245724582459246024612462246324642465246624672468246924702471247224732474247524762477247824792480248124822483248424852486248724882489249024912492249324942495249624972498249925002501250225032504250525062507250825092510251125122513251425152516251725182519252025212522252325242525252625272528252925302531253225332534253525362537253825392540254125422543254425452546254725482549255025512552255325542555255625572558255925602561256225632564256525662567256825692570257125722573257425752576257725782579258025812582258325842585258625872588258925902591259225932594259525962597259825992600260126022603260426052606260726082609261026112612261326142615261626172618261926202621262226232624262526262627262826292630263126322633263426352636263726382639264026412642264326442645264626472648264926502651265226532654265526562657265826592660266126622663266426652666266726682669267026712672267326742675267626772678267926802681268226832684268526862687268826892690269126922693269426952696269726982699270027012702270327042705270627072708270927102711271227132714271527162717271827192720272127222723272427252726272727282729273027312732273327342735273627372738273927402741274227432744274527462747274827492750275127522753275427552756275727582759276027612762276327642765276627672768276927702771277227732774277527762777277827792780278127822783278427852786278727882789279027912792279327942795279627972798279928002801280228032804280528062807280828092810281128122813281428152816281728182819282028212822282328242825282628272828282928302831283228332834283528362837283828392840284128422843284428452846284728482849285028512852285328542855285628572858285928602861286228632864286528662867286828692870287128722873287428752876287728782879288028812882288328842885288628872888288928902891289228932894289528962897289828992900290129022903290429052906290729082909291029112912291329142915291629172918291929202921292229232924292529262927292829292930293129322933293429352936293729382939294029412942294329442945294629472948294929502951295229532954295529562957295829592960296129622963296429652966296729682969297029712972297329742975297629772978297929802981298229832984298529862987298829892990299129922993299429952996299729982999300030013002300330043005300630073008300930103011301230133014301530163017301830193020302130223023302430253026302730283029303030313032303330343035303630373038303930403041304230433044304530463047304830493050305130523053305430553056305730583059306030613062306330643065306630673068306930703071307230733074307530763077307830793080308130823083308430853086308730883089309030913092309330943095309630973098309931003101310231033104310531063107310831093110311131123113311431153116311731183119312031213122312331243125312631273128312931303131313231333134313531363137313831393140314131423143314431453146314731483149315031513152315331543155315631573158315931603161316231633164316531663167316831693170317131723173317431753176
  1. /*
  2. Reprap firmware based on Sprinter
  3. Optimize for Sanguinololu 1.2 and above, RAMPS
  4. This program is free software: you can redistribute it and/or modify
  5. it under the terms of the GNU General Public License as published by
  6. the Free Software Foundation, either version 3 of the License, or
  7. (at your option) any later version.
  8. This program is distributed in the hope that it will be useful,
  9. but WITHOUT ANY WARRANTY; without even the implied warranty of
  10. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  11. GNU General Public License for more details.
  12. You should have received a copy of the GNU General Public License
  13. along with this program. If not, see <http://www.gnu.org/licenses/>. */
  14. /*
  15. This firmware is a mashup between Sprinter,grbl and parts from marlin.
  16. (https://github.com/kliment/Sprinter)
  17. Changes by Doppler Michael (midopple)
  18. Planner is from Simen Svale Skogsrud
  19. https://github.com/simen/grbl
  20. Parts of Marlin Firmware from ErikZalm
  21. https://github.com/ErikZalm/Marlin-non-gen6
  22. Sprinter Changelog
  23. - Look forward function --> calculate 16 Steps forward, get from Firmaware Marlin and Grbl
  24. - Stepper control with Timer 1 (Interrupt)
  25. - Extruder heating with PID use a Softpwm (Timer 2) with 500 hz to free Timer1 für Steppercontrol
  26. - command M220 Sxxx --> tune Printing speed online (+/- 50 %)
  27. - G2 / G3 command --> circle funktion
  28. - Baudrate set to 250 kbaud
  29. - Testet on Sanguinololu Board
  30. - M30 Command can delete files on SD Card
  31. - move string to flash to free RAM vor forward planner
  32. - M203 Temperature monitor for Repetier
  33. Version 1.3.04T
  34. - Implement Plannercode from Marlin V1 big thanks to Erik
  35. - Stepper interrupt with Step loops
  36. - Stepperfrequenz 30 Khz
  37. - New Command
  38. * M202 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
  39. * M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) im mm/sec^2
  40. * M205 - advanced settings: minimum travel speed S=while printing T=travel only, X= maximum xy jerk, Z=maximum Z jerk
  41. - Remove unused Variables
  42. - Check Uart Puffer while circle processing (CMD: G2 / G3)
  43. - Fast Xfer Function --> move Text to Flash
  44. - Option to deaktivate ARC (G2/G3) function (save flash)
  45. - Removed modulo (%) operator, which uses an expensive divide
  46. Version 1.3.05T
  47. - changed homing function to not conflict with min_software_endstops/max_software_endstops (thanks rGlory)
  48. - Changed check in arc_func
  49. - Corrected distance calculation. (thanks jv4779)
  50. - MAX Feed Rate for Z-Axis reduced to 2 mm/s some Printers had problems with 4 mm/s
  51. Version 1.3.06T
  52. - the microcontroller can store settings in the EEPROM
  53. - M500 - stores paramters in EEPROM
  54. - M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
  55. - M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
  56. - M503 - Print settings
  57. Version 1.3.07T
  58. - Optimize Variable Size (faster Code)
  59. - Remove unused Code from Interrupt --> faster ~ 22 us per step
  60. - Replace abs with fabs --> Faster and smaler
  61. - Add "store_eeprom.cpp" to makefile
  62. Version 1.3.08T
  63. - If a line starts with ';', it is ignored but comment_mode is reset.
  64. A ';' inside a line ignores just the portion following the ';' character.
  65. The beginning of the line is still interpreted.
  66. - Same fix for SD Card, testet and work
  67. Version 1.3.09T
  68. - Move SLOWDOWN Function up
  69. Version 1.3.10T
  70. - Add info to GEN7 Pins
  71. - Update pins.h for gen7, working setup for 20MHz
  72. - calculate feedrate without extrude before planner block is set
  73. - New Board --> GEN7 @ 20 Mhz …
  74. - ENDSTOPS_ONLY_FOR_HOMING Option ignore Endstop always --> fault is cleared
  75. Version 1.3.11T
  76. - fix for broken include in store_eeprom.cpp --> Thanks to kmeehl (issue #145)
  77. - Make fastio & Arduino pin numbering consistent for AT90USB128x. --> Thanks to lincomatic
  78. - Select Speedtable with F_CPU
  79. - Use same Values for Speedtables as Marlin
  80. -
  81. */
  82. #include <avr/pgmspace.h>
  83. #include <math.h>
  84. #include "fastio.h"
  85. #include "Configuration.h"
  86. #include "pins.h"
  87. #include "Sprinter.h"
  88. #include "speed_lookuptable.h"
  89. #include "heater.h"
  90. #ifdef USE_ARC_FUNCTION
  91. #include "arc_func.h"
  92. #endif
  93. #ifdef SDSUPPORT
  94. #include "SdFat.h"
  95. #endif
  96. #ifdef USE_EEPROM_SETTINGS
  97. #include "store_eeprom.h"
  98. #endif
  99. #ifndef CRITICAL_SECTION_START
  100. #define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli()
  101. #define CRITICAL_SECTION_END SREG = _sreg
  102. #endif //CRITICAL_SECTION_START
  103. void __cxa_pure_virtual(){};
  104. // look here for descriptions of gcodes: http://linuxcnc.org/handbook/gcode/g-code.html
  105. // http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
  106. //Implemented Codes
  107. //-------------------
  108. // G0 -> G1
  109. // G1 - Coordinated Movement X Y Z E
  110. // G2 - CW ARC
  111. // G3 - CCW ARC
  112. // G4 - Dwell S<seconds> or P<milliseconds>
  113. // G28 - Home all Axis
  114. // G90 - Use Absolute Coordinates
  115. // G91 - Use Relative Coordinates
  116. // G92 - Set current position to cordinates given
  117. //RepRap M Codes
  118. // M104 - Set extruder target temp
  119. // M105 - Read current temp
  120. // M106 - Fan on
  121. // M107 - Fan off
  122. // M109 - Wait for extruder current temp to reach target temp.
  123. // M114 - Display current position
  124. //Custom M Codes
  125. // M20 - List SD card
  126. // M21 - Init SD card
  127. // M22 - Release SD card
  128. // M23 - Select SD file (M23 filename.g)
  129. // M24 - Start/resume SD print
  130. // M25 - Pause SD print
  131. // M26 - Set SD position in bytes (M26 S12345)
  132. // M27 - Report SD print status
  133. // M28 - Start SD write (M28 filename.g)
  134. // M29 - Stop SD write
  135. // - <filename> - Delete file on sd card
  136. // M42 - Set output on free pins, on a non pwm pin (over pin 13 on an arduino mega) use S255 to turn it on and S0 to turn it off. Use P to decide the pin (M42 P23 S255) would turn pin 23 on
  137. // M80 - Turn on Power Supply
  138. // M81 - Turn off Power Supply
  139. // M82 - Set E codes absolute (default)
  140. // M83 - Set E codes relative while in Absolute Coordinates (G90) mode
  141. // M84 - Disable steppers until next move,
  142. // or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
  143. // M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
  144. // M92 - Set axis_steps_per_unit - same syntax as G92
  145. // M115 - Capabilities string
  146. // M119 - Show Endstopper State
  147. // M140 - Set bed target temp
  148. // M190 - Wait for bed current temp to reach target temp.
  149. // M201 - Set maximum acceleration in units/s^2 for print moves (M201 X1000 Y1000)
  150. // M202 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
  151. // M203 - Set temperture monitor to Sx
  152. // M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) im mm/sec^2
  153. // M205 - advanced settings: minimum travel speed S=while printing T=travel only, X= maximum xy jerk, Z=maximum Z jerk
  154. // M220 - set speed factor override percentage S:factor in percent
  155. // M500 - stores paramters in EEPROM
  156. // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
  157. // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
  158. // M503 - Print settings
  159. // Debug feature / Testing the PID for Hotend
  160. // M601 - Show Temp jitter from Extruder (min / max value from Hotend Temperatur while printing)
  161. // M602 - Reset Temp jitter from Extruder (min / max val) --> Dont use it while Printing
  162. // M603 - Show Free Ram
  163. #define _VERSION_TEXT "1.3.11T / 19.03.2012"
  164. //Stepper Movement Variables
  165. char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
  166. float axis_steps_per_unit[4] = _AXIS_STEP_PER_UNIT;
  167. float max_feedrate[4] = _MAX_FEEDRATE;
  168. float homing_feedrate[] = _HOMING_FEEDRATE;
  169. bool axis_relative_modes[] = _AXIS_RELATIVE_MODES;
  170. float move_acceleration = _ACCELERATION; // Normal acceleration mm/s^2
  171. float retract_acceleration = _RETRACT_ACCELERATION; // Normal acceleration mm/s^2
  172. float max_xy_jerk = _MAX_XY_JERK;
  173. float max_z_jerk = _MAX_Z_JERK;
  174. long max_acceleration_units_per_sq_second[4] = _MAX_ACCELERATION_UNITS_PER_SQ_SECOND; // X, Y, Z and E max acceleration in mm/s^2 for printing moves or retracts
  175. //float max_start_speed_units_per_second[] = _MAX_START_SPEED_UNITS_PER_SECOND;
  176. //long max_travel_acceleration_units_per_sq_second[] = _MAX_TRAVEL_ACCELERATION_UNITS_PER_SQ_SECOND; // X, Y, Z max acceleration in mm/s^2 for travel moves
  177. float mintravelfeedrate = DEFAULT_MINTRAVELFEEDRATE;
  178. float minimumfeedrate = DEFAULT_MINIMUMFEEDRATE;
  179. unsigned long axis_steps_per_sqr_second[NUM_AXIS];
  180. unsigned long plateau_steps;
  181. //unsigned long axis_max_interval[NUM_AXIS];
  182. //unsigned long axis_travel_steps_per_sqr_second[NUM_AXIS];
  183. //unsigned long max_interval;
  184. //unsigned long steps_per_sqr_second;
  185. //adjustable feed faktor for online tuning printerspeed
  186. volatile int feedmultiply=100; //100->original / 200-> Faktor 2 / 50 -> Faktor 0.5
  187. int saved_feedmultiply;
  188. volatile bool feedmultiplychanged=false;
  189. //boolean acceleration_enabled = false, accelerating = false;
  190. //unsigned long interval;
  191. float destination[NUM_AXIS] = {0.0, 0.0, 0.0, 0.0};
  192. float current_position[NUM_AXIS] = {0.0, 0.0, 0.0, 0.0};
  193. bool home_all_axis = true;
  194. //unsigned ?? ToDo: Check
  195. int feedrate = 1500, next_feedrate, saved_feedrate;
  196. long gcode_N, gcode_LastN;
  197. bool relative_mode = false; //Determines Absolute or Relative Coordinates
  198. //unsigned long steps_taken[NUM_AXIS];
  199. //long axis_interval[NUM_AXIS]; // for speed delay
  200. //float time_for_move;
  201. //bool relative_mode_e = false; //Determines Absolute or Relative E Codes while in Absolute Coordinates mode. E is always relative in Relative Coordinates mode.
  202. //long timediff = 0;
  203. bool is_homing = false;
  204. //experimental feedrate calc
  205. //float d = 0;
  206. //float axis_diff[NUM_AXIS] = {0, 0, 0, 0};
  207. #ifdef USE_ARC_FUNCTION
  208. //For arc centerpont, send bei Command G2/G3
  209. float offset[3] = {0.0, 0.0, 0.0};
  210. #endif
  211. #ifdef STEP_DELAY_RATIO
  212. long long_step_delay_ratio = STEP_DELAY_RATIO * 100;
  213. #endif
  214. ///oscillation reduction
  215. #ifdef RAPID_OSCILLATION_REDUCTION
  216. float cumm_wait_time_in_dir[NUM_AXIS]={0.0,0.0,0.0,0.0};
  217. bool prev_move_direction[NUM_AXIS]={1,1,1,1};
  218. float osc_wait_remainder = 0.0;
  219. #endif
  220. // comm variables and Commandbuffer
  221. // BUFSIZE is reduced from 8 to 6 to free more RAM for the PLANNER
  222. #define MAX_CMD_SIZE 96
  223. #define BUFSIZE 6 //8
  224. char cmdbuffer[BUFSIZE][MAX_CMD_SIZE];
  225. bool fromsd[BUFSIZE];
  226. //Need 1kb Ram --> only work with Atmega1284
  227. #ifdef SD_FAST_XFER_AKTIV
  228. char fastxferbuffer[SD_FAST_XFER_CHUNK_SIZE + 1];
  229. int lastxferchar;
  230. long xferbytes;
  231. #endif
  232. unsigned char bufindr = 0;
  233. unsigned char bufindw = 0;
  234. unsigned char buflen = 0;
  235. char serial_char;
  236. int serial_count = 0;
  237. boolean comment_mode = false;
  238. char *strchr_pointer; // just a pointer to find chars in the cmd string like X, Y, Z, E, etc
  239. //Send Temperature in °C to Host
  240. int hotendtC = 0, bedtempC = 0;
  241. //Inactivity shutdown variables
  242. unsigned long previous_millis_cmd = 0;
  243. unsigned long max_inactive_time = 0;
  244. unsigned long stepper_inactive_time = 0;
  245. //Temp Montor for repetier
  246. unsigned char manage_monitor = 255;
  247. //------------------------------------------------
  248. //Init the SD card
  249. //------------------------------------------------
  250. #ifdef SDSUPPORT
  251. Sd2Card card;
  252. SdVolume volume;
  253. SdFile root;
  254. SdFile file;
  255. uint32_t filesize = 0;
  256. uint32_t sdpos = 0;
  257. bool sdmode = false;
  258. bool sdactive = false;
  259. bool savetosd = false;
  260. int16_t read_char_int;
  261. void initsd()
  262. {
  263. sdactive = false;
  264. #if SDSS >- 1
  265. if(root.isOpen())
  266. root.close();
  267. if (!card.init(SPI_FULL_SPEED,SDSS)){
  268. //if (!card.init(SPI_HALF_SPEED,SDSS))
  269. showString(PSTR("SD init fail\r\n"));
  270. }
  271. else if (!volume.init(&card))
  272. showString(PSTR("volume.init failed\r\n"));
  273. else if (!root.openRoot(&volume))
  274. showString(PSTR("openRoot failed\r\n"));
  275. else{
  276. sdactive = true;
  277. print_disk_info();
  278. #ifdef SDINITFILE
  279. file.close();
  280. if(file.open(&root, "init.g", O_READ)){
  281. sdpos = 0;
  282. filesize = file.fileSize();
  283. sdmode = true;
  284. }
  285. #endif
  286. }
  287. #endif
  288. }
  289. #ifdef SD_FAST_XFER_AKTIV
  290. #ifdef PIDTEMP
  291. extern int g_heater_pwm_val;
  292. #endif
  293. void fast_xfer()
  294. {
  295. char *pstr;
  296. boolean done = false;
  297. //force heater pins low
  298. if(HEATER_0_PIN > -1) WRITE(HEATER_0_PIN,LOW);
  299. if(HEATER_1_PIN > -1) WRITE(HEATER_1_PIN,LOW);
  300. g_heater_pwm_val = 0;
  301. lastxferchar = 1;
  302. xferbytes = 0;
  303. pstr = strstr(strchr_pointer+4, " ");
  304. if(pstr == NULL)
  305. {
  306. showString(PSTR("invalid command\r\n"));
  307. return;
  308. }
  309. *pstr = '\0';
  310. //check mode (currently only RAW is supported
  311. if(strcmp(strchr_pointer+4, "RAW") != 0)
  312. {
  313. showString(PSTR("Invalid transfer codec\r\n"));
  314. return;
  315. }else{
  316. showString(PSTR("Selected codec: "));
  317. Serial.println(strchr_pointer+4);
  318. }
  319. if (!file.open(&root, pstr+1, O_CREAT | O_APPEND | O_WRITE | O_TRUNC))
  320. {
  321. showString(PSTR("open failed, File: "));
  322. Serial.print(pstr+1);
  323. showString(PSTR("."));
  324. }else{
  325. showString(PSTR("Writing to file: "));
  326. Serial.println(pstr+1);
  327. }
  328. showString(PSTR("ok\r\n"));
  329. //RAW transfer codec
  330. //Host sends \0 then up to SD_FAST_XFER_CHUNK_SIZE then \0
  331. //when host is done, it sends \0\0.
  332. //if a non \0 character is recieved at the beginning, host has failed somehow, kill the transfer.
  333. //read SD_FAST_XFER_CHUNK_SIZE bytes (or until \0 is recieved)
  334. while(!done)
  335. {
  336. while(!Serial.available())
  337. {
  338. }
  339. if(Serial.read() != 0)
  340. {
  341. //host has failed, this isn't a RAW chunk, it's an actual command
  342. file.sync();
  343. file.close();
  344. return;
  345. }
  346. for(int i=0;i<SD_FAST_XFER_CHUNK_SIZE+1;i++)
  347. {
  348. while(!Serial.available())
  349. {
  350. }
  351. lastxferchar = Serial.read();
  352. //buffer the data...
  353. fastxferbuffer[i] = lastxferchar;
  354. xferbytes++;
  355. if(lastxferchar == 0)
  356. break;
  357. }
  358. if(fastxferbuffer[0] != 0)
  359. {
  360. fastxferbuffer[SD_FAST_XFER_CHUNK_SIZE] = 0;
  361. file.write(fastxferbuffer);
  362. showString(PSTR("ok\r\n"));
  363. }else{
  364. showString(PSTR("Wrote "));
  365. Serial.print(xferbytes);
  366. showString(PSTR(" bytes.\r\n"));
  367. done = true;
  368. }
  369. }
  370. file.sync();
  371. file.close();
  372. }
  373. #endif
  374. void print_disk_info(void)
  375. {
  376. // print the type of card
  377. showString(PSTR("\nCard type: "));
  378. switch(card.type())
  379. {
  380. case SD_CARD_TYPE_SD1:
  381. showString(PSTR("SD1\r\n"));
  382. break;
  383. case SD_CARD_TYPE_SD2:
  384. showString(PSTR("SD2\r\n"));
  385. break;
  386. case SD_CARD_TYPE_SDHC:
  387. showString(PSTR("SDHC\r\n"));
  388. break;
  389. default:
  390. showString(PSTR("Unknown\r\n"));
  391. }
  392. //uint64_t freeSpace = volume.clusterCount()*volume.blocksPerCluster()*512;
  393. //uint64_t occupiedSpace = (card.cardSize()*512) - freeSpace;
  394. // print the type and size of the first FAT-type volume
  395. uint32_t volumesize;
  396. showString(PSTR("\nVolume type is FAT"));
  397. Serial.println(volume.fatType(), DEC);
  398. volumesize = volume.blocksPerCluster(); // clusters are collections of blocks
  399. volumesize *= volume.clusterCount(); // we'll have a lot of clusters
  400. volumesize *= 512; // SD card blocks are always 512 bytes
  401. volumesize /= 1024; //kbytes
  402. volumesize /= 1024; //Mbytes
  403. showString(PSTR("Volume size (Mbytes): "));
  404. Serial.println(volumesize);
  405. // list all files in the card with date and size
  406. //root.ls(LS_R | LS_DATE | LS_SIZE);
  407. }
  408. FORCE_INLINE void write_command(char *buf)
  409. {
  410. char* begin = buf;
  411. char* npos = 0;
  412. char* end = buf + strlen(buf) - 1;
  413. file.writeError = false;
  414. if((npos = strchr(buf, 'N')) != NULL)
  415. {
  416. begin = strchr(npos, ' ') + 1;
  417. end = strchr(npos, '*') - 1;
  418. }
  419. end[1] = '\r';
  420. end[2] = '\n';
  421. end[3] = '\0';
  422. //Serial.println(begin);
  423. file.write(begin);
  424. if (file.writeError)
  425. {
  426. showString(PSTR("error writing to file\r\n"));
  427. }
  428. }
  429. #endif
  430. int FreeRam1(void)
  431. {
  432. extern int __bss_end;
  433. extern int* __brkval;
  434. int free_memory;
  435. if (reinterpret_cast<int>(__brkval) == 0)
  436. {
  437. // if no heap use from end of bss section
  438. free_memory = reinterpret_cast<int>(&free_memory) - reinterpret_cast<int>(&__bss_end);
  439. }
  440. else
  441. {
  442. // use from top of stack to heap
  443. free_memory = reinterpret_cast<int>(&free_memory) - reinterpret_cast<int>(__brkval);
  444. }
  445. return free_memory;
  446. }
  447. //------------------------------------------------
  448. //Print a String from Flash to Serial (save RAM)
  449. //------------------------------------------------
  450. void showString (PGM_P s)
  451. {
  452. char c;
  453. while ((c = pgm_read_byte(s++)) != 0)
  454. Serial.print(c);
  455. }
  456. //------------------------------------------------
  457. // Init
  458. //------------------------------------------------
  459. void setup()
  460. {
  461. Serial.begin(BAUDRATE);
  462. showString(PSTR("Sprinter\r\n"));
  463. showString(PSTR(_VERSION_TEXT));
  464. showString(PSTR("\r\n"));
  465. showString(PSTR("start\r\n"));
  466. for(int i = 0; i < BUFSIZE; i++)
  467. {
  468. fromsd[i] = false;
  469. }
  470. //Initialize Dir Pins
  471. #if X_DIR_PIN > -1
  472. SET_OUTPUT(X_DIR_PIN);
  473. #endif
  474. #if Y_DIR_PIN > -1
  475. SET_OUTPUT(Y_DIR_PIN);
  476. #endif
  477. #if Z_DIR_PIN > -1
  478. SET_OUTPUT(Z_DIR_PIN);
  479. #endif
  480. #if E_DIR_PIN > -1
  481. SET_OUTPUT(E_DIR_PIN);
  482. #endif
  483. //Initialize Enable Pins - steppers default to disabled.
  484. #if (X_ENABLE_PIN > -1)
  485. SET_OUTPUT(X_ENABLE_PIN);
  486. if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
  487. #endif
  488. #if (Y_ENABLE_PIN > -1)
  489. SET_OUTPUT(Y_ENABLE_PIN);
  490. if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
  491. #endif
  492. #if (Z_ENABLE_PIN > -1)
  493. SET_OUTPUT(Z_ENABLE_PIN);
  494. if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
  495. #endif
  496. #if (E_ENABLE_PIN > -1)
  497. SET_OUTPUT(E_ENABLE_PIN);
  498. if(!E_ENABLE_ON) WRITE(E_ENABLE_PIN,HIGH);
  499. #endif
  500. #ifdef CONTROLLERFAN_PIN
  501. SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
  502. #endif
  503. //endstops and pullups
  504. #ifdef ENDSTOPPULLUPS
  505. #if X_MIN_PIN > -1
  506. SET_INPUT(X_MIN_PIN);
  507. WRITE(X_MIN_PIN,HIGH);
  508. #endif
  509. #if X_MAX_PIN > -1
  510. SET_INPUT(X_MAX_PIN);
  511. WRITE(X_MAX_PIN,HIGH);
  512. #endif
  513. #if Y_MIN_PIN > -1
  514. SET_INPUT(Y_MIN_PIN);
  515. WRITE(Y_MIN_PIN,HIGH);
  516. #endif
  517. #if Y_MAX_PIN > -1
  518. SET_INPUT(Y_MAX_PIN);
  519. WRITE(Y_MAX_PIN,HIGH);
  520. #endif
  521. #if Z_MIN_PIN > -1
  522. SET_INPUT(Z_MIN_PIN);
  523. WRITE(Z_MIN_PIN,HIGH);
  524. #endif
  525. #if Z_MAX_PIN > -1
  526. SET_INPUT(Z_MAX_PIN);
  527. WRITE(Z_MAX_PIN,HIGH);
  528. #endif
  529. #else
  530. #if X_MIN_PIN > -1
  531. SET_INPUT(X_MIN_PIN);
  532. #endif
  533. #if X_MAX_PIN > -1
  534. SET_INPUT(X_MAX_PIN);
  535. #endif
  536. #if Y_MIN_PIN > -1
  537. SET_INPUT(Y_MIN_PIN);
  538. #endif
  539. #if Y_MAX_PIN > -1
  540. SET_INPUT(Y_MAX_PIN);
  541. #endif
  542. #if Z_MIN_PIN > -1
  543. SET_INPUT(Z_MIN_PIN);
  544. #endif
  545. #if Z_MAX_PIN > -1
  546. SET_INPUT(Z_MAX_PIN);
  547. #endif
  548. #endif
  549. #if (HEATER_0_PIN > -1)
  550. SET_OUTPUT(HEATER_0_PIN);
  551. WRITE(HEATER_0_PIN,LOW);
  552. #endif
  553. #if (HEATER_1_PIN > -1)
  554. SET_OUTPUT(HEATER_1_PIN);
  555. WRITE(HEATER_1_PIN,LOW);
  556. #endif
  557. //Initialize Fan Pin
  558. #if (FAN_PIN > -1)
  559. SET_OUTPUT(FAN_PIN);
  560. #endif
  561. //Initialize Alarm Pin
  562. #if (ALARM_PIN > -1)
  563. SET_OUTPUT(ALARM_PIN);
  564. WRITE(ALARM_PIN,LOW);
  565. #endif
  566. //Initialize LED Pin
  567. #if (LED_PIN > -1)
  568. SET_OUTPUT(LED_PIN);
  569. WRITE(LED_PIN,LOW);
  570. #endif
  571. //Initialize Step Pins
  572. #if (X_STEP_PIN > -1)
  573. SET_OUTPUT(X_STEP_PIN);
  574. #endif
  575. #if (Y_STEP_PIN > -1)
  576. SET_OUTPUT(Y_STEP_PIN);
  577. #endif
  578. #if (Z_STEP_PIN > -1)
  579. SET_OUTPUT(Z_STEP_PIN);
  580. #endif
  581. #if (E_STEP_PIN > -1)
  582. SET_OUTPUT(E_STEP_PIN);
  583. #endif
  584. for(int8_t i=0; i < NUM_AXIS; i++)
  585. {
  586. axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i];
  587. }
  588. // for(int i=0; i < NUM_AXIS; i++){
  589. // axis_max_interval[i] = 100000000.0 / (max_start_speed_units_per_second[i] * axis_steps_per_unit[i]);
  590. // axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i];
  591. // axis_travel_steps_per_sqr_second[i] = max_travel_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i];
  592. // }
  593. #ifdef HEATER_USES_MAX6675
  594. SET_OUTPUT(SCK_PIN);
  595. WRITE(SCK_PIN,0);
  596. SET_OUTPUT(MOSI_PIN);
  597. WRITE(MOSI_PIN,1);
  598. SET_INPUT(MISO_PIN);
  599. WRITE(MISO_PIN,1);
  600. SET_OUTPUT(MAX6675_SS);
  601. WRITE(MAX6675_SS,1);
  602. #endif
  603. #ifdef SDSUPPORT
  604. //power to SD reader
  605. #if SDPOWER > -1
  606. SET_OUTPUT(SDPOWER);
  607. WRITE(SDPOWER,HIGH);
  608. #endif
  609. showString(PSTR("SD Start\r\n"));
  610. initsd();
  611. #endif
  612. #ifdef PID_SOFT_PWM
  613. showString(PSTR("Soft PWM Init\r\n"));
  614. init_Timer2_softpwm();
  615. #endif
  616. showString(PSTR("Planner Init\r\n"));
  617. plan_init(); // Initialize planner;
  618. showString(PSTR("Stepper Timer init\r\n"));
  619. st_init(); // Initialize stepper
  620. #ifdef USE_EEPROM_SETTINGS
  621. //first Value --> Init with default
  622. //second value --> Print settings to UART
  623. EEPROM_RetrieveSettings(false,false);
  624. #endif
  625. //Free Ram
  626. showString(PSTR("Free Ram: "));
  627. Serial.println(FreeRam1());
  628. //Planner Buffer Size
  629. showString(PSTR("Plan Buffer Size:"));
  630. Serial.print((int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
  631. showString(PSTR(" / "));
  632. Serial.println(BLOCK_BUFFER_SIZE);
  633. }
  634. //------------------------------------------------
  635. //MAIN LOOP
  636. //------------------------------------------------
  637. void loop()
  638. {
  639. if(buflen < (BUFSIZE-1))
  640. get_command();
  641. if(buflen)
  642. {
  643. #ifdef SDSUPPORT
  644. if(savetosd)
  645. {
  646. if(strstr(cmdbuffer[bufindr],"M29") == NULL)
  647. {
  648. write_command(cmdbuffer[bufindr]);
  649. showString(PSTR("ok\r\n"));
  650. }
  651. else
  652. {
  653. file.sync();
  654. file.close();
  655. savetosd = false;
  656. showString(PSTR("Done saving file.\r\n"));
  657. }
  658. }
  659. else
  660. {
  661. process_commands();
  662. }
  663. #else
  664. process_commands();
  665. #endif
  666. buflen = (buflen-1);
  667. //bufindr = (bufindr + 1)%BUFSIZE;
  668. //Removed modulo (%) operator, which uses an expensive divide and multiplication
  669. bufindr++;
  670. if(bufindr == BUFSIZE) bufindr = 0;
  671. }
  672. //check heater every n milliseconds
  673. manage_heater();
  674. manage_inactivity(1);
  675. }
  676. //------------------------------------------------
  677. //Check Uart buffer while arc function ist calc a circle
  678. //------------------------------------------------
  679. void check_buffer_while_arc()
  680. {
  681. if(buflen < (BUFSIZE-1))
  682. {
  683. get_command();
  684. }
  685. }
  686. //------------------------------------------------
  687. //READ COMMAND FROM UART
  688. //------------------------------------------------
  689. void get_command()
  690. {
  691. while( Serial.available() > 0 && buflen < BUFSIZE)
  692. {
  693. serial_char = Serial.read();
  694. if(serial_char == '\n' || serial_char == '\r' || serial_char == ':' || serial_count >= (MAX_CMD_SIZE - 1) )
  695. {
  696. if(!serial_count) { //if empty line
  697. comment_mode = false; // for new command
  698. return;
  699. }
  700. cmdbuffer[bufindw][serial_count] = 0; //terminate string
  701. fromsd[bufindw] = false;
  702. if(strstr(cmdbuffer[bufindw], "N") != NULL)
  703. {
  704. strchr_pointer = strchr(cmdbuffer[bufindw], 'N');
  705. gcode_N = (strtol(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL, 10));
  706. if(gcode_N != gcode_LastN+1 && (strstr(cmdbuffer[bufindw], "M110") == NULL) )
  707. {
  708. showString(PSTR("Serial Error: Line Number is not Last Line Number+1, Last Line:"));
  709. Serial.println(gcode_LastN);
  710. //Serial.println(gcode_N);
  711. FlushSerialRequestResend();
  712. serial_count = 0;
  713. return;
  714. }
  715. if(strstr(cmdbuffer[bufindw], "*") != NULL)
  716. {
  717. byte checksum = 0;
  718. byte count = 0;
  719. while(cmdbuffer[bufindw][count] != '*') checksum = checksum^cmdbuffer[bufindw][count++];
  720. strchr_pointer = strchr(cmdbuffer[bufindw], '*');
  721. if( (int)(strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)) != checksum)
  722. {
  723. showString(PSTR("Error: checksum mismatch, Last Line:"));
  724. Serial.println(gcode_LastN);
  725. FlushSerialRequestResend();
  726. serial_count = 0;
  727. return;
  728. }
  729. //if no errors, continue parsing
  730. }
  731. else
  732. {
  733. showString(PSTR("Error: No Checksum with line number, Last Line:"));
  734. Serial.println(gcode_LastN);
  735. FlushSerialRequestResend();
  736. serial_count = 0;
  737. return;
  738. }
  739. gcode_LastN = gcode_N;
  740. //if no errors, continue parsing
  741. }
  742. else // if we don't receive 'N' but still see '*'
  743. {
  744. if((strstr(cmdbuffer[bufindw], "*") != NULL))
  745. {
  746. showString(PSTR("Error: No Line Number with checksum, Last Line:"));
  747. Serial.println(gcode_LastN);
  748. serial_count = 0;
  749. return;
  750. }
  751. }
  752. if((strstr(cmdbuffer[bufindw], "G") != NULL))
  753. {
  754. strchr_pointer = strchr(cmdbuffer[bufindw], 'G');
  755. switch((int)((strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL))))
  756. {
  757. case 0:
  758. case 1:
  759. #ifdef USE_ARC_FUNCTION
  760. case 2: //G2
  761. case 3: //G3 arc func
  762. #endif
  763. #ifdef SDSUPPORT
  764. if(savetosd)
  765. break;
  766. #endif
  767. showString(PSTR("ok\r\n"));
  768. //Serial.println("ok");
  769. break;
  770. default:
  771. break;
  772. }
  773. }
  774. //Removed modulo (%) operator, which uses an expensive divide and multiplication
  775. //bufindw = (bufindw + 1)%BUFSIZE;
  776. bufindw++;
  777. if(bufindw == BUFSIZE) bufindw = 0;
  778. buflen += 1;
  779. comment_mode = false; //for new command
  780. serial_count = 0; //clear buffer
  781. }
  782. else
  783. {
  784. if(serial_char == ';') comment_mode = true;
  785. if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char;
  786. }
  787. }
  788. #ifdef SDSUPPORT
  789. if(!sdmode || serial_count!=0)
  790. {
  791. return;
  792. }
  793. while( filesize > sdpos && buflen < BUFSIZE)
  794. {
  795. serial_char = file.read();
  796. read_char_int = (int)serial_char;
  797. if(serial_char == '\n' || serial_char == '\r' || serial_char == ':' || serial_count >= (MAX_CMD_SIZE - 1) || read_char_int == -1)
  798. {
  799. sdpos = file.curPosition();
  800. if(sdpos >= filesize)
  801. {
  802. sdmode = false;
  803. showString(PSTR("Done printing file\r\n"));
  804. }
  805. if(!serial_count) { //if empty line
  806. comment_mode = false; // for new command
  807. return;
  808. }
  809. cmdbuffer[bufindw][serial_count] = 0; //terminate string
  810. fromsd[bufindw] = true;
  811. buflen += 1;
  812. //Removed modulo (%) operator, which uses an expensive divide and multiplication
  813. //bufindw = (bufindw + 1)%BUFSIZE;
  814. bufindw++;
  815. if(bufindw == BUFSIZE) bufindw = 0;
  816. comment_mode = false; //for new command
  817. serial_count = 0; //clear buffer
  818. }
  819. else
  820. {
  821. if(serial_char == ';') comment_mode = true;
  822. if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char;
  823. }
  824. }
  825. #endif
  826. }
  827. static bool check_endstops = true;
  828. void enable_endstops(bool check)
  829. {
  830. check_endstops = check;
  831. }
  832. FORCE_INLINE float code_value() { return (strtod(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL)); }
  833. FORCE_INLINE long code_value_long() { return (strtol(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL, 10)); }
  834. FORCE_INLINE bool code_seen(char code_string[]) { return (strstr(cmdbuffer[bufindr], code_string) != NULL); } //Return True if the string was found
  835. FORCE_INLINE bool code_seen(char code)
  836. {
  837. strchr_pointer = strchr(cmdbuffer[bufindr], code);
  838. return (strchr_pointer != NULL); //Return True if a character was found
  839. }
  840. //------------------------------------------------
  841. // CHECK COMMAND AND CONVERT VALUES
  842. //------------------------------------------------
  843. FORCE_INLINE void process_commands()
  844. {
  845. unsigned long codenum; //throw away variable
  846. char *starpos = NULL;
  847. if(code_seen('G'))
  848. {
  849. switch((int)code_value())
  850. {
  851. case 0: // G0 -> G1
  852. case 1: // G1
  853. #if (defined DISABLE_CHECK_DURING_ACC) || (defined DISABLE_CHECK_DURING_MOVE) || (defined DISABLE_CHECK_DURING_TRAVEL)
  854. manage_heater();
  855. #endif
  856. get_coordinates(); // For X Y Z E F
  857. prepare_move();
  858. previous_millis_cmd = millis();
  859. //ClearToSend();
  860. return;
  861. //break;
  862. #ifdef USE_ARC_FUNCTION
  863. case 2: // G2 - CW ARC
  864. get_arc_coordinates();
  865. prepare_arc_move(true);
  866. previous_millis_cmd = millis();
  867. //break;
  868. return;
  869. case 3: // G3 - CCW ARC
  870. get_arc_coordinates();
  871. prepare_arc_move(false);
  872. previous_millis_cmd = millis();
  873. //break;
  874. return;
  875. #endif
  876. case 4: // G4 dwell
  877. codenum = 0;
  878. if(code_seen('P')) codenum = code_value(); // milliseconds to wait
  879. if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait
  880. codenum += millis(); // keep track of when we started waiting
  881. while(millis() < codenum ){
  882. manage_heater();
  883. }
  884. break;
  885. case 28: //G28 Home all Axis one at a time
  886. saved_feedrate = feedrate;
  887. saved_feedmultiply = feedmultiply;
  888. previous_millis_cmd = millis();
  889. feedmultiply = 100;
  890. enable_endstops(true);
  891. for(int i=0; i < NUM_AXIS; i++)
  892. {
  893. destination[i] = current_position[i];
  894. }
  895. feedrate = 0;
  896. is_homing = true;
  897. home_all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2])));
  898. if((home_all_axis) || (code_seen(axis_codes[X_AXIS])))
  899. {
  900. if ((X_MIN_PIN > -1 && X_HOME_DIR==-1) || (X_MAX_PIN > -1 && X_HOME_DIR==1))
  901. {
  902. st_synchronize();
  903. current_position[X_AXIS] = -1.5 * X_MAX_LENGTH * X_HOME_DIR;
  904. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  905. destination[X_AXIS] = 0;
  906. feedrate = homing_feedrate[X_AXIS];
  907. prepare_move();
  908. st_synchronize();
  909. current_position[X_AXIS] = 5 * X_HOME_DIR;
  910. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  911. destination[X_AXIS] = 0;
  912. prepare_move();
  913. st_synchronize();
  914. current_position[X_AXIS] = -10 * X_HOME_DIR;
  915. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  916. destination[X_AXIS] = 0;
  917. feedrate = homing_feedrate[X_AXIS]/2 ;
  918. prepare_move();
  919. st_synchronize();
  920. current_position[X_AXIS] = (X_HOME_DIR == -1) ? 0 : X_MAX_LENGTH;
  921. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  922. destination[X_AXIS] = current_position[X_AXIS];
  923. feedrate = 0;
  924. }
  925. }
  926. //showString(PSTR("HOME X AXIS\r\n"));
  927. if((home_all_axis) || (code_seen(axis_codes[Y_AXIS])))
  928. {
  929. if ((Y_MIN_PIN > -1 && Y_HOME_DIR==-1) || (Y_MAX_PIN > -1 && Y_HOME_DIR==1))
  930. {
  931. current_position[Y_AXIS] = -1.5 * Y_MAX_LENGTH * Y_HOME_DIR;
  932. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  933. destination[Y_AXIS] = 0;
  934. feedrate = homing_feedrate[Y_AXIS];
  935. prepare_move();
  936. st_synchronize();
  937. current_position[Y_AXIS] = 5 * Y_HOME_DIR;
  938. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  939. destination[Y_AXIS] = 0;
  940. prepare_move();
  941. st_synchronize();
  942. current_position[Y_AXIS] = -10 * Y_HOME_DIR;
  943. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  944. destination[Y_AXIS] = 0;
  945. feedrate = homing_feedrate[Y_AXIS]/2;
  946. prepare_move();
  947. st_synchronize();
  948. current_position[Y_AXIS] = (Y_HOME_DIR == -1) ? 0 : Y_MAX_LENGTH;
  949. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  950. destination[Y_AXIS] = current_position[Y_AXIS];
  951. feedrate = 0;
  952. }
  953. }
  954. //showString(PSTR("HOME Y AXIS\r\n"));
  955. if((home_all_axis) || (code_seen(axis_codes[Z_AXIS])))
  956. {
  957. if ((Z_MIN_PIN > -1 && Z_HOME_DIR==-1) || (Z_MAX_PIN > -1 && Z_HOME_DIR==1))
  958. {
  959. current_position[Z_AXIS] = -1.5 * Z_MAX_LENGTH * Z_HOME_DIR;
  960. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  961. destination[Z_AXIS] = 0;
  962. feedrate = homing_feedrate[Z_AXIS];
  963. prepare_move();
  964. st_synchronize();
  965. current_position[Z_AXIS] = 2 * Z_HOME_DIR;
  966. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  967. destination[Z_AXIS] = 0;
  968. prepare_move();
  969. st_synchronize();
  970. current_position[Z_AXIS] = -3 * Z_HOME_DIR;
  971. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  972. destination[Z_AXIS] = 0;
  973. feedrate = homing_feedrate[Z_AXIS]/2;
  974. prepare_move();
  975. st_synchronize();
  976. current_position[Z_AXIS] = (Z_HOME_DIR == -1) ? 0 : Z_MAX_LENGTH;
  977. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  978. destination[Z_AXIS] = current_position[Z_AXIS];
  979. feedrate = 0;
  980. }
  981. }
  982. //showString(PSTR("HOME Z AXIS\r\n"));
  983. #ifdef ENDSTOPS_ONLY_FOR_HOMING
  984. enable_endstops(false);
  985. #endif
  986. is_homing = false;
  987. feedrate = saved_feedrate;
  988. feedmultiply = saved_feedmultiply;
  989. previous_millis_cmd = millis();
  990. break;
  991. case 90: // G90
  992. relative_mode = false;
  993. break;
  994. case 91: // G91
  995. relative_mode = true;
  996. break;
  997. case 92: // G92
  998. if(!code_seen(axis_codes[E_AXIS]))
  999. st_synchronize();
  1000. for(int i=0; i < NUM_AXIS; i++)
  1001. {
  1002. if(code_seen(axis_codes[i])) current_position[i] = code_value();
  1003. }
  1004. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1005. break;
  1006. default:
  1007. #ifdef SEND_WRONG_CMD_INFO
  1008. showString(PSTR("Unknown G-COM:"));
  1009. Serial.println(cmdbuffer[bufindr]);
  1010. #endif
  1011. break;
  1012. }
  1013. }
  1014. else if(code_seen('M'))
  1015. {
  1016. switch( (int)code_value() )
  1017. {
  1018. #ifdef SDSUPPORT
  1019. case 20: // M20 - list SD card
  1020. showString(PSTR("Begin file list\r\n"));
  1021. root.ls();
  1022. showString(PSTR("End file list\r\n"));
  1023. break;
  1024. case 21: // M21 - init SD card
  1025. sdmode = false;
  1026. initsd();
  1027. break;
  1028. case 22: //M22 - release SD card
  1029. sdmode = false;
  1030. sdactive = false;
  1031. break;
  1032. case 23: //M23 - Select file
  1033. if(sdactive)
  1034. {
  1035. sdmode = false;
  1036. file.close();
  1037. starpos = (strchr(strchr_pointer + 4,'*'));
  1038. if(starpos!=NULL)
  1039. *(starpos-1)='\0';
  1040. if (file.open(&root, strchr_pointer + 4, O_READ))
  1041. {
  1042. showString(PSTR("File opened:"));
  1043. Serial.print(strchr_pointer + 4);
  1044. showString(PSTR(" Size:"));
  1045. Serial.println(file.fileSize());
  1046. sdpos = 0;
  1047. filesize = file.fileSize();
  1048. showString(PSTR("File selected\r\n"));
  1049. }
  1050. else
  1051. {
  1052. showString(PSTR("file.open failed\r\n"));
  1053. }
  1054. }
  1055. break;
  1056. case 24: //M24 - Start SD print
  1057. if(sdactive)
  1058. {
  1059. sdmode = true;
  1060. }
  1061. break;
  1062. case 25: //M25 - Pause SD print
  1063. if(sdmode)
  1064. {
  1065. sdmode = false;
  1066. }
  1067. break;
  1068. case 26: //M26 - Set SD index
  1069. if(sdactive && code_seen('S'))
  1070. {
  1071. sdpos = code_value_long();
  1072. file.seekSet(sdpos);
  1073. }
  1074. break;
  1075. case 27: //M27 - Get SD status
  1076. if(sdactive)
  1077. {
  1078. showString(PSTR("SD printing byte "));
  1079. Serial.print(sdpos);
  1080. showString(PSTR("/"));
  1081. Serial.println(filesize);
  1082. }
  1083. else
  1084. {
  1085. showString(PSTR("Not SD printing\r\n"));
  1086. }
  1087. break;
  1088. case 28: //M28 - Start SD write
  1089. if(sdactive)
  1090. {
  1091. char* npos = 0;
  1092. file.close();
  1093. sdmode = false;
  1094. starpos = (strchr(strchr_pointer + 4,'*'));
  1095. if(starpos != NULL)
  1096. {
  1097. npos = strchr(cmdbuffer[bufindr], 'N');
  1098. strchr_pointer = strchr(npos,' ') + 1;
  1099. *(starpos-1) = '\0';
  1100. }
  1101. if (!file.open(&root, strchr_pointer+4, O_CREAT | O_APPEND | O_WRITE | O_TRUNC))
  1102. {
  1103. showString(PSTR("open failed, File: "));
  1104. Serial.print(strchr_pointer + 4);
  1105. showString(PSTR("."));
  1106. }
  1107. else
  1108. {
  1109. savetosd = true;
  1110. showString(PSTR("Writing to file: "));
  1111. Serial.println(strchr_pointer + 4);
  1112. }
  1113. }
  1114. break;
  1115. case 29: //M29 - Stop SD write
  1116. //processed in write to file routine above
  1117. //savetosd = false;
  1118. break;
  1119. #ifndef SD_FAST_XFER_AKTIV
  1120. case 30: // M30 filename - Delete file
  1121. if(sdactive)
  1122. {
  1123. sdmode = false;
  1124. file.close();
  1125. starpos = (strchr(strchr_pointer + 4,'*'));
  1126. if(starpos!=NULL)
  1127. *(starpos-1)='\0';
  1128. if(file.remove(&root, strchr_pointer + 4))
  1129. {
  1130. showString(PSTR("File deleted\r\n"));
  1131. }
  1132. else
  1133. {
  1134. showString(PSTR("Deletion failed\r\n"));
  1135. }
  1136. }
  1137. break;
  1138. #else
  1139. case 30: //M30 - fast SD transfer
  1140. fast_xfer();
  1141. break;
  1142. case 31: //M31 - high speed xfer capabilities
  1143. showString(PSTR("RAW:"));
  1144. Serial.println(SD_FAST_XFER_CHUNK_SIZE);
  1145. break;
  1146. #endif
  1147. #endif
  1148. case 42: //M42 -Change pin status via gcode
  1149. if (code_seen('S'))
  1150. {
  1151. int pin_status = code_value();
  1152. if (code_seen('P') && pin_status >= 0 && pin_status <= 255)
  1153. {
  1154. int pin_number = code_value();
  1155. for(int i = 0; i < sizeof(sensitive_pins); i++)
  1156. {
  1157. if (sensitive_pins[i] == pin_number)
  1158. {
  1159. pin_number = -1;
  1160. break;
  1161. }
  1162. }
  1163. if (pin_number > -1)
  1164. {
  1165. pinMode(pin_number, OUTPUT);
  1166. digitalWrite(pin_number, pin_status);
  1167. //analogWrite(pin_number, pin_status);
  1168. }
  1169. }
  1170. }
  1171. break;
  1172. case 104: // M104
  1173. if (code_seen('S')) target_raw = temp2analogh(target_temp = code_value());
  1174. #ifdef WATCHPERIOD
  1175. if(target_raw > current_raw)
  1176. {
  1177. watchmillis = max(1,millis());
  1178. watch_raw = current_raw;
  1179. }
  1180. else
  1181. {
  1182. watchmillis = 0;
  1183. }
  1184. #endif
  1185. break;
  1186. case 140: // M140 set bed temp
  1187. #if TEMP_1_PIN > -1 || defined BED_USES_AD595
  1188. if (code_seen('S')) target_bed_raw = temp2analogBed(code_value());
  1189. #endif
  1190. break;
  1191. case 105: // M105
  1192. #if (TEMP_0_PIN > -1) || defined (HEATER_USES_MAX6675)|| defined HEATER_USES_AD595
  1193. hotendtC = analog2temp(current_raw);
  1194. #endif
  1195. #if TEMP_1_PIN > -1 || defined BED_USES_AD595
  1196. bedtempC = analog2tempBed(current_bed_raw);
  1197. #endif
  1198. #if (TEMP_0_PIN > -1) || defined (HEATER_USES_MAX6675) || defined HEATER_USES_AD595
  1199. showString(PSTR("ok T:"));
  1200. Serial.print(hotendtC);
  1201. #ifdef PIDTEMP
  1202. showString(PSTR(" @:"));
  1203. Serial.print(heater_duty);
  1204. /*
  1205. showString(PSTR(",P:"));
  1206. Serial.print(pTerm);
  1207. showString(PSTR(",I:"));
  1208. Serial.print(iTerm);
  1209. showString(PSTR(",D:"));
  1210. Serial.print(dTerm);
  1211. */
  1212. #ifdef AUTOTEMP
  1213. showString(PSTR(",AU:"));
  1214. Serial.print(autotemp_setpoint);
  1215. #endif
  1216. #endif
  1217. #if TEMP_1_PIN > -1 || defined BED_USES_AD595
  1218. showString(PSTR(" B:"));
  1219. Serial.println(bedtempC);
  1220. #else
  1221. Serial.println();
  1222. #endif
  1223. #else
  1224. #error No temperature source available
  1225. #endif
  1226. return;
  1227. //break;
  1228. case 109: { // M109 - Wait for extruder heater to reach target.
  1229. if (code_seen('S')) target_raw = temp2analogh(target_temp = code_value());
  1230. #ifdef WATCHPERIOD
  1231. if(target_raw>current_raw)
  1232. {
  1233. watchmillis = max(1,millis());
  1234. watch_raw = current_raw;
  1235. }
  1236. else
  1237. {
  1238. watchmillis = 0;
  1239. }
  1240. #endif
  1241. codenum = millis();
  1242. /* See if we are heating up or cooling down */
  1243. bool target_direction = (current_raw < target_raw); // true if heating, false if cooling
  1244. #ifdef TEMP_RESIDENCY_TIME
  1245. long residencyStart;
  1246. residencyStart = -1;
  1247. /* continue to loop until we have reached the target temp
  1248. _and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */
  1249. while( (target_direction ? (current_raw < target_raw) : (current_raw > target_raw))
  1250. || (residencyStart > -1 && (millis() - residencyStart) < TEMP_RESIDENCY_TIME*1000) ) {
  1251. #else
  1252. while ( target_direction ? (current_raw < target_raw) : (current_raw > target_raw) ) {
  1253. #endif
  1254. if( (millis() - codenum) > 1000 ) //Print Temp Reading every 1 second while heating up/cooling down
  1255. {
  1256. showString(PSTR("T:"));
  1257. Serial.println( analog2temp(current_raw) );
  1258. codenum = millis();
  1259. }
  1260. manage_heater();
  1261. #ifdef TEMP_RESIDENCY_TIME
  1262. /* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
  1263. or when current temp falls outside the hysteresis after target temp was reached */
  1264. if ( (residencyStart == -1 && target_direction && current_raw >= target_raw)
  1265. || (residencyStart == -1 && !target_direction && current_raw <= target_raw)
  1266. || (residencyStart > -1 && labs(analog2temp(current_raw) - analog2temp(target_raw)) > TEMP_HYSTERESIS) ) {
  1267. residencyStart = millis();
  1268. }
  1269. #endif
  1270. }
  1271. }
  1272. break;
  1273. case 190: // M190 - Wait bed for heater to reach target.
  1274. #if TEMP_1_PIN > -1
  1275. if (code_seen('S')) target_bed_raw = temp2analogBed(code_value());
  1276. codenum = millis();
  1277. while(current_bed_raw < target_bed_raw)
  1278. {
  1279. if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
  1280. {
  1281. hotendtC=analog2temp(current_raw);
  1282. showString(PSTR("T:"));
  1283. Serial.print( hotendtC );
  1284. showString(PSTR(" B:"));
  1285. Serial.println( analog2tempBed(current_bed_raw) );
  1286. codenum = millis();
  1287. }
  1288. manage_heater();
  1289. }
  1290. #endif
  1291. break;
  1292. #if FAN_PIN > -1
  1293. case 106: //M106 Fan On
  1294. if (code_seen('S'))
  1295. {
  1296. WRITE(FAN_PIN, HIGH);
  1297. //analogWrite(FAN_PIN, constrain(code_value(),0,255) );
  1298. }
  1299. else
  1300. {
  1301. WRITE(FAN_PIN, HIGH);
  1302. //analogWrite(FAN_PIN, 255 );
  1303. }
  1304. break;
  1305. case 107: //M107 Fan Off
  1306. //analogWrite(FAN_PIN, 0);
  1307. WRITE(FAN_PIN, LOW);
  1308. break;
  1309. #endif
  1310. #if (PS_ON_PIN > -1)
  1311. case 80: // M81 - ATX Power On
  1312. SET_OUTPUT(PS_ON_PIN); //GND
  1313. break;
  1314. case 81: // M81 - ATX Power Off
  1315. SET_INPUT(PS_ON_PIN); //Floating
  1316. break;
  1317. #endif
  1318. case 82:
  1319. axis_relative_modes[3] = false;
  1320. break;
  1321. case 83:
  1322. axis_relative_modes[3] = true;
  1323. break;
  1324. case 84:
  1325. st_synchronize(); // wait for all movements to finish
  1326. if(code_seen('S'))
  1327. {
  1328. stepper_inactive_time = code_value() * 1000;
  1329. }
  1330. else
  1331. {
  1332. disable_x();
  1333. disable_y();
  1334. disable_z();
  1335. disable_e();
  1336. }
  1337. break;
  1338. case 85: // M85
  1339. code_seen('S');
  1340. max_inactive_time = code_value() * 1000;
  1341. break;
  1342. case 92: // M92
  1343. for(int i=0; i < NUM_AXIS; i++)
  1344. {
  1345. if(code_seen(axis_codes[i])) axis_steps_per_unit[i] = code_value();
  1346. }
  1347. // Update start speed intervals and axis order. TODO: refactor axis_max_interval[] calculation into a function, as it
  1348. // should also be used in setup() as well
  1349. // long temp_max_intervals[NUM_AXIS];
  1350. // for(int i=0; i < NUM_AXIS; i++)
  1351. // {
  1352. // axis_max_interval[i] = 100000000.0 / (max_start_speed_units_per_second[i] * axis_steps_per_unit[i]);//TODO: do this for
  1353. // all steps_per_unit related variables
  1354. // }
  1355. break;
  1356. case 115: // M115
  1357. showString(PSTR("FIRMWARE_NAME: Sprinter Experimental PROTOCOL_VERSION:1.0 MACHINE_TYPE:Mendel EXTRUDER_COUNT:1\r\n"));
  1358. //Serial.println(uuid);
  1359. showString(PSTR(_DEF_CHAR_UUID));
  1360. showString(PSTR("\r\n"));
  1361. break;
  1362. case 114: // M114
  1363. showString(PSTR("X:"));
  1364. Serial.print(current_position[0]);
  1365. showString(PSTR("Y:"));
  1366. Serial.print(current_position[1]);
  1367. showString(PSTR("Z:"));
  1368. Serial.print(current_position[2]);
  1369. showString(PSTR("E:"));
  1370. Serial.println(current_position[3]);
  1371. break;
  1372. case 119: // M119
  1373. #if (X_MIN_PIN > -1)
  1374. showString(PSTR("x_min:"));
  1375. Serial.print((READ(X_MIN_PIN)^X_ENDSTOP_INVERT)?"H ":"L ");
  1376. #endif
  1377. #if (X_MAX_PIN > -1)
  1378. showString(PSTR("x_max:"));
  1379. Serial.print((READ(X_MAX_PIN)^X_ENDSTOP_INVERT)?"H ":"L ");
  1380. #endif
  1381. #if (Y_MIN_PIN > -1)
  1382. showString(PSTR("y_min:"));
  1383. Serial.print((READ(Y_MIN_PIN)^Y_ENDSTOP_INVERT)?"H ":"L ");
  1384. #endif
  1385. #if (Y_MAX_PIN > -1)
  1386. showString(PSTR("y_max:"));
  1387. Serial.print((READ(Y_MAX_PIN)^Y_ENDSTOP_INVERT)?"H ":"L ");
  1388. #endif
  1389. #if (Z_MIN_PIN > -1)
  1390. showString(PSTR("z_min:"));
  1391. Serial.print((READ(Z_MIN_PIN)^Z_ENDSTOP_INVERT)?"H ":"L ");
  1392. #endif
  1393. #if (Z_MAX_PIN > -1)
  1394. showString(PSTR("z_max:"));
  1395. Serial.print((READ(Z_MAX_PIN)^Z_ENDSTOP_INVERT)?"H ":"L ");
  1396. #endif
  1397. showString(PSTR("\r\n"));
  1398. break;
  1399. case 201: // M201
  1400. for(int8_t i=0; i < NUM_AXIS; i++)
  1401. {
  1402. if(code_seen(axis_codes[i]))
  1403. {
  1404. max_acceleration_units_per_sq_second[i] = code_value();
  1405. axis_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i];
  1406. }
  1407. }
  1408. #if 0 // Not used for Sprinter/grbl gen6
  1409. case 202: // M202
  1410. for(int i=0; i < NUM_AXIS; i++)
  1411. {
  1412. if(code_seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i];
  1413. }
  1414. break;
  1415. #else
  1416. case 202: // M202 max feedrate mm/sec
  1417. for(int8_t i=0; i < NUM_AXIS; i++)
  1418. {
  1419. if(code_seen(axis_codes[i])) max_feedrate[i] = code_value();
  1420. }
  1421. break;
  1422. #endif
  1423. case 203: // M203 Temperature monitor
  1424. if(code_seen('S')) manage_monitor = code_value();
  1425. if(manage_monitor==100) manage_monitor=1; // Set 100 to heated bed
  1426. break;
  1427. case 204: // M204 acclereration S normal moves T filmanent only moves
  1428. if(code_seen('S')) move_acceleration = code_value() ;
  1429. if(code_seen('T')) retract_acceleration = code_value() ;
  1430. break;
  1431. case 205: //M205 advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
  1432. if(code_seen('S')) minimumfeedrate = code_value();
  1433. if(code_seen('T')) mintravelfeedrate = code_value();
  1434. //if(code_seen('B')) minsegmenttime = code_value() ;
  1435. if(code_seen('X')) max_xy_jerk = code_value() ;
  1436. if(code_seen('Z')) max_z_jerk = code_value() ;
  1437. break;
  1438. case 220: // M220 S<factor in percent>- set speed factor override percentage
  1439. {
  1440. if(code_seen('S'))
  1441. {
  1442. feedmultiply = code_value() ;
  1443. if(feedmultiply < 20) feedmultiply = 20;
  1444. if(feedmultiply > 200) feedmultiply = 200;
  1445. feedmultiplychanged=true;
  1446. }
  1447. }
  1448. break;
  1449. #ifdef USE_EEPROM_SETTINGS
  1450. case 500: // Store settings in EEPROM
  1451. {
  1452. EEPROM_StoreSettings();
  1453. }
  1454. break;
  1455. case 501: // Read settings from EEPROM
  1456. {
  1457. EEPROM_RetrieveSettings(false,true);
  1458. }
  1459. break;
  1460. case 502: // Revert to default settings
  1461. {
  1462. EEPROM_RetrieveSettings(true,true);
  1463. }
  1464. break;
  1465. case 503: // print settings currently in memory
  1466. {
  1467. EEPROM_printSettings();
  1468. }
  1469. break;
  1470. #endif
  1471. #ifdef DEBUG_HEATER_TEMP
  1472. case 601: // M601 show Extruder Temp jitter
  1473. #if (TEMP_0_PIN > -1) || defined (HEATER_USES_MAX6675)|| defined HEATER_USES_AD595
  1474. if(current_raw_maxval > 0)
  1475. tt_maxval = analog2temp(current_raw_maxval);
  1476. if(current_raw_minval < 10000)
  1477. tt_minval = analog2temp(current_raw_minval);
  1478. #endif
  1479. showString(PSTR("Tmin:"));
  1480. Serial.print(tt_minval);
  1481. showString(PSTR(" / Tmax:"));
  1482. Serial.print(tt_maxval);
  1483. showString(PSTR(" "));
  1484. break;
  1485. case 602: // M602 reset Extruder Temp jitter
  1486. current_raw_minval = 32000;
  1487. current_raw_maxval = -32000;
  1488. showString(PSTR("T Minmax Reset "));
  1489. break;
  1490. #endif
  1491. case 603: // M603 Free RAM
  1492. showString(PSTR("Free Ram: "));
  1493. Serial.println(FreeRam1());
  1494. break;
  1495. default:
  1496. #ifdef SEND_WRONG_CMD_INFO
  1497. showString(PSTR("Unknown M-COM:"));
  1498. Serial.println(cmdbuffer[bufindr]);
  1499. #endif
  1500. break;
  1501. }
  1502. }
  1503. else{
  1504. showString(PSTR("Unknown command:\r\n"));
  1505. Serial.println(cmdbuffer[bufindr]);
  1506. }
  1507. ClearToSend();
  1508. }
  1509. void FlushSerialRequestResend()
  1510. {
  1511. //char cmdbuffer[bufindr][100]="Resend:";
  1512. Serial.flush();
  1513. showString(PSTR("Resend:"));
  1514. Serial.println(gcode_LastN + 1);
  1515. ClearToSend();
  1516. }
  1517. void ClearToSend()
  1518. {
  1519. previous_millis_cmd = millis();
  1520. #ifdef SDSUPPORT
  1521. if(fromsd[bufindr])
  1522. return;
  1523. #endif
  1524. showString(PSTR("ok\r\n"));
  1525. //Serial.println("ok");
  1526. }
  1527. FORCE_INLINE void get_coordinates()
  1528. {
  1529. for(int i=0; i < NUM_AXIS; i++)
  1530. {
  1531. if(code_seen(axis_codes[i])) destination[i] = (float)code_value() + (axis_relative_modes[i] || relative_mode)*current_position[i];
  1532. else destination[i] = current_position[i]; //Are these else lines really needed?
  1533. }
  1534. if(code_seen('F'))
  1535. {
  1536. next_feedrate = code_value();
  1537. if(next_feedrate > 0.0) feedrate = next_feedrate;
  1538. }
  1539. }
  1540. #ifdef USE_ARC_FUNCTION
  1541. FORCE_INLINE void get_arc_coordinates()
  1542. {
  1543. get_coordinates();
  1544. if(code_seen('I')) offset[0] = code_value();
  1545. if(code_seen('J')) offset[1] = code_value();
  1546. }
  1547. #endif
  1548. void prepare_move()
  1549. {
  1550. long help_feedrate = 0;
  1551. if(!is_homing){
  1552. if (min_software_endstops)
  1553. {
  1554. if (destination[X_AXIS] < 0) destination[X_AXIS] = 0.0;
  1555. if (destination[Y_AXIS] < 0) destination[Y_AXIS] = 0.0;
  1556. if (destination[Z_AXIS] < 0) destination[Z_AXIS] = 0.0;
  1557. }
  1558. if (max_software_endstops)
  1559. {
  1560. if (destination[X_AXIS] > X_MAX_LENGTH) destination[X_AXIS] = X_MAX_LENGTH;
  1561. if (destination[Y_AXIS] > Y_MAX_LENGTH) destination[Y_AXIS] = Y_MAX_LENGTH;
  1562. if (destination[Z_AXIS] > Z_MAX_LENGTH) destination[Z_AXIS] = Z_MAX_LENGTH;
  1563. }
  1564. }
  1565. help_feedrate = ((long)feedrate*(long)feedmultiply);
  1566. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], help_feedrate/6000.0);
  1567. for(int i=0; i < NUM_AXIS; i++)
  1568. {
  1569. current_position[i] = destination[i];
  1570. }
  1571. }
  1572. #ifdef USE_ARC_FUNCTION
  1573. void prepare_arc_move(char isclockwise)
  1574. {
  1575. float r = hypot(offset[X_AXIS], offset[Y_AXIS]); // Compute arc radius for mc_arc
  1576. long help_feedrate = 0;
  1577. help_feedrate = ((long)feedrate*(long)feedmultiply);
  1578. // Trace the arc
  1579. mc_arc(current_position, destination, offset, X_AXIS, Y_AXIS, Z_AXIS, help_feedrate/6000.0, r, isclockwise);
  1580. // As far as the parser is concerned, the position is now == target. In reality the
  1581. // motion control system might still be processing the action and the real tool position
  1582. // in any intermediate location.
  1583. for(int8_t i=0; i < NUM_AXIS; i++)
  1584. {
  1585. current_position[i] = destination[i];
  1586. }
  1587. }
  1588. #endif
  1589. FORCE_INLINE void kill()
  1590. {
  1591. #if TEMP_0_PIN > -1
  1592. target_raw=0;
  1593. WRITE(HEATER_0_PIN,LOW);
  1594. #endif
  1595. #if TEMP_1_PIN > -1
  1596. target_bed_raw=0;
  1597. if(HEATER_1_PIN > -1) WRITE(HEATER_1_PIN,LOW);
  1598. #endif
  1599. disable_x();
  1600. disable_y();
  1601. disable_z();
  1602. disable_e();
  1603. if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT);
  1604. }
  1605. FORCE_INLINE void manage_inactivity(byte debug)
  1606. {
  1607. if( (millis()-previous_millis_cmd) > max_inactive_time ) if(max_inactive_time) kill();
  1608. if( (millis()-previous_millis_cmd) > stepper_inactive_time ) if(stepper_inactive_time)
  1609. {
  1610. disable_x();
  1611. disable_y();
  1612. disable_z();
  1613. disable_e();
  1614. }
  1615. check_axes_activity();
  1616. }
  1617. // Planner with Interrupt for Stepper
  1618. /*
  1619. Reasoning behind the mathematics in this module (in the key of 'Mathematica'):
  1620. s == speed, a == acceleration, t == time, d == distance
  1621. Basic definitions:
  1622. Speed[s_, a_, t_] := s + (a*t)
  1623. Travel[s_, a_, t_] := Integrate[Speed[s, a, t], t]
  1624. Distance to reach a specific speed with a constant acceleration:
  1625. Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, d, t]
  1626. d -> (m^2 - s^2)/(2 a) --> estimate_acceleration_distance()
  1627. Speed after a given distance of travel with constant acceleration:
  1628. Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, m, t]
  1629. m -> Sqrt[2 a d + s^2]
  1630. DestinationSpeed[s_, a_, d_] := Sqrt[2 a d + s^2]
  1631. When to start braking (di) to reach a specified destionation speed (s2) after accelerating
  1632. from initial speed s1 without ever stopping at a plateau:
  1633. Solve[{DestinationSpeed[s1, a, di] == DestinationSpeed[s2, a, d - di]}, di]
  1634. di -> (2 a d - s1^2 + s2^2)/(4 a) --> intersection_distance()
  1635. IntersectionDistance[s1_, s2_, a_, d_] := (2 a d - s1^2 + s2^2)/(4 a)
  1636. */
  1637. static block_t block_buffer[BLOCK_BUFFER_SIZE]; // A ring buffer for motion instructions
  1638. static volatile unsigned char block_buffer_head; // Index of the next block to be pushed
  1639. static volatile unsigned char block_buffer_tail; // Index of the block to process now
  1640. //===========================================================================
  1641. //=============================private variables ============================
  1642. //===========================================================================
  1643. // Returns the index of the next block in the ring buffer
  1644. // NOTE: Removed modulo (%) operator, which uses an expensive divide and multiplication.
  1645. static int8_t next_block_index(int8_t block_index) {
  1646. block_index++;
  1647. if (block_index == BLOCK_BUFFER_SIZE) { block_index = 0; }
  1648. return(block_index);
  1649. }
  1650. // Returns the index of the previous block in the ring buffer
  1651. static int8_t prev_block_index(int8_t block_index) {
  1652. if (block_index == 0) { block_index = BLOCK_BUFFER_SIZE; }
  1653. block_index--;
  1654. return(block_index);
  1655. }
  1656. // The current position of the tool in absolute steps
  1657. static long position[4];
  1658. static float previous_speed[4]; // Speed of previous path line segment
  1659. static float previous_nominal_speed; // Nominal speed of previous path line segment
  1660. // Calculates the distance (not time) it takes to accelerate from initial_rate to target_rate using the
  1661. // given acceleration:
  1662. FORCE_INLINE float estimate_acceleration_distance(float initial_rate, float target_rate, float acceleration)
  1663. {
  1664. if (acceleration!=0) {
  1665. return((target_rate*target_rate-initial_rate*initial_rate)/
  1666. (2.0*acceleration));
  1667. }
  1668. else {
  1669. return 0.0; // acceleration was 0, set acceleration distance to 0
  1670. }
  1671. }
  1672. // This function gives you the point at which you must start braking (at the rate of -acceleration) if
  1673. // you started at speed initial_rate and accelerated until this point and want to end at the final_rate after
  1674. // a total travel of distance. This can be used to compute the intersection point between acceleration and
  1675. // deceleration in the cases where the trapezoid has no plateau (i.e. never reaches maximum speed)
  1676. FORCE_INLINE float intersection_distance(float initial_rate, float final_rate, float acceleration, float distance)
  1677. {
  1678. if (acceleration!=0) {
  1679. return((2.0*acceleration*distance-initial_rate*initial_rate+final_rate*final_rate)/
  1680. (4.0*acceleration) );
  1681. }
  1682. else {
  1683. return 0.0; // acceleration was 0, set intersection distance to 0
  1684. }
  1685. }
  1686. // Calculates trapezoid parameters so that the entry- and exit-speed is compensated by the provided factors.
  1687. void calculate_trapezoid_for_block(block_t *block, float entry_factor, float exit_factor) {
  1688. unsigned long initial_rate = ceil(block->nominal_rate*entry_factor); // (step/min)
  1689. unsigned long final_rate = ceil(block->nominal_rate*exit_factor); // (step/min)
  1690. // Limit minimal step rate (Otherwise the timer will overflow.)
  1691. if(initial_rate <120) {initial_rate=120; }
  1692. if(final_rate < 120) {final_rate=120; }
  1693. long acceleration = block->acceleration_st;
  1694. int32_t accelerate_steps =
  1695. ceil(estimate_acceleration_distance(block->initial_rate, block->nominal_rate, acceleration));
  1696. int32_t decelerate_steps =
  1697. floor(estimate_acceleration_distance(block->nominal_rate, block->final_rate, -acceleration));
  1698. // Calculate the size of Plateau of Nominal Rate.
  1699. int32_t plateau_steps = block->step_event_count-accelerate_steps-decelerate_steps;
  1700. // Is the Plateau of Nominal Rate smaller than nothing? That means no cruising, and we will
  1701. // have to use intersection_distance() to calculate when to abort acceleration and start braking
  1702. // in order to reach the final_rate exactly at the end of this block.
  1703. if (plateau_steps < 0) {
  1704. accelerate_steps = ceil(
  1705. intersection_distance(block->initial_rate, block->final_rate, acceleration, block->step_event_count));
  1706. accelerate_steps = max(accelerate_steps,0); // Check limits due to numerical round-off
  1707. accelerate_steps = min(accelerate_steps,block->step_event_count);
  1708. plateau_steps = 0;
  1709. }
  1710. #ifdef ADVANCE
  1711. volatile long initial_advance = block->advance*entry_factor*entry_factor;
  1712. volatile long final_advance = block->advance*exit_factor*exit_factor;
  1713. #endif // ADVANCE
  1714. // block->accelerate_until = accelerate_steps;
  1715. // block->decelerate_after = accelerate_steps+plateau_steps;
  1716. CRITICAL_SECTION_START; // Fill variables used by the stepper in a critical section
  1717. if(block->busy == false) { // Don't update variables if block is busy.
  1718. block->accelerate_until = accelerate_steps;
  1719. block->decelerate_after = accelerate_steps+plateau_steps;
  1720. block->initial_rate = initial_rate;
  1721. block->final_rate = final_rate;
  1722. #ifdef ADVANCE
  1723. block->initial_advance = initial_advance;
  1724. block->final_advance = final_advance;
  1725. #endif //ADVANCE
  1726. }
  1727. CRITICAL_SECTION_END;
  1728. }
  1729. // Calculates the maximum allowable speed at this point when you must be able to reach target_velocity using the
  1730. // acceleration within the allotted distance.
  1731. FORCE_INLINE float max_allowable_speed(float acceleration, float target_velocity, float distance) {
  1732. return sqrt(target_velocity*target_velocity-2*acceleration*distance);
  1733. }
  1734. // "Junction jerk" in this context is the immediate change in speed at the junction of two blocks.
  1735. // This method will calculate the junction jerk as the euclidean distance between the nominal
  1736. // velocities of the respective blocks.
  1737. //inline float junction_jerk(block_t *before, block_t *after) {
  1738. // return sqrt(
  1739. // pow((before->speed_x-after->speed_x), 2)+pow((before->speed_y-after->speed_y), 2));
  1740. //}
  1741. // The kernel called by planner_recalculate() when scanning the plan from last to first entry.
  1742. void planner_reverse_pass_kernel(block_t *previous, block_t *current, block_t *next) {
  1743. if(!current) { return; }
  1744. if (next) {
  1745. // If entry speed is already at the maximum entry speed, no need to recheck. Block is cruising.
  1746. // If not, block in state of acceleration or deceleration. Reset entry speed to maximum and
  1747. // check for maximum allowable speed reductions to ensure maximum possible planned speed.
  1748. if (current->entry_speed != current->max_entry_speed) {
  1749. // If nominal length true, max junction speed is guaranteed to be reached. Only compute
  1750. // for max allowable speed if block is decelerating and nominal length is false.
  1751. if ((!current->nominal_length_flag) && (current->max_entry_speed > next->entry_speed)) {
  1752. current->entry_speed = min( current->max_entry_speed,
  1753. max_allowable_speed(-current->acceleration,next->entry_speed,current->millimeters));
  1754. } else {
  1755. current->entry_speed = current->max_entry_speed;
  1756. }
  1757. current->recalculate_flag = true;
  1758. }
  1759. } // Skip last block. Already initialized and set for recalculation.
  1760. }
  1761. // planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This
  1762. // implements the reverse pass.
  1763. void planner_reverse_pass() {
  1764. uint8_t block_index = block_buffer_head;
  1765. if(((block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1)) > 3) {
  1766. block_index = (block_buffer_head - 3) & (BLOCK_BUFFER_SIZE - 1);
  1767. block_t *block[3] = { NULL, NULL, NULL };
  1768. while(block_index != block_buffer_tail) {
  1769. block_index = prev_block_index(block_index);
  1770. block[2]= block[1];
  1771. block[1]= block[0];
  1772. block[0] = &block_buffer[block_index];
  1773. planner_reverse_pass_kernel(block[0], block[1], block[2]);
  1774. }
  1775. }
  1776. }
  1777. // The kernel called by planner_recalculate() when scanning the plan from first to last entry.
  1778. void planner_forward_pass_kernel(block_t *previous, block_t *current, block_t *next) {
  1779. if(!previous) { return; }
  1780. // If the previous block is an acceleration block, but it is not long enough to complete the
  1781. // full speed change within the block, we need to adjust the entry speed accordingly. Entry
  1782. // speeds have already been reset, maximized, and reverse planned by reverse planner.
  1783. // If nominal length is true, max junction speed is guaranteed to be reached. No need to recheck.
  1784. if (!previous->nominal_length_flag) {
  1785. if (previous->entry_speed < current->entry_speed) {
  1786. double entry_speed = min( current->entry_speed,
  1787. max_allowable_speed(-previous->acceleration,previous->entry_speed,previous->millimeters) );
  1788. // Check for junction speed change
  1789. if (current->entry_speed != entry_speed) {
  1790. current->entry_speed = entry_speed;
  1791. current->recalculate_flag = true;
  1792. }
  1793. }
  1794. }
  1795. }
  1796. // planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This
  1797. // implements the forward pass.
  1798. void planner_forward_pass() {
  1799. uint8_t block_index = block_buffer_tail;
  1800. block_t *block[3] = { NULL, NULL, NULL };
  1801. while(block_index != block_buffer_head) {
  1802. block[0] = block[1];
  1803. block[1] = block[2];
  1804. block[2] = &block_buffer[block_index];
  1805. planner_forward_pass_kernel(block[0],block[1],block[2]);
  1806. block_index = next_block_index(block_index);
  1807. }
  1808. planner_forward_pass_kernel(block[1], block[2], NULL);
  1809. }
  1810. // Recalculates the trapezoid speed profiles for all blocks in the plan according to the
  1811. // entry_factor for each junction. Must be called by planner_recalculate() after
  1812. // updating the blocks.
  1813. void planner_recalculate_trapezoids() {
  1814. int8_t block_index = block_buffer_tail;
  1815. block_t *current;
  1816. block_t *next = NULL;
  1817. while(block_index != block_buffer_head) {
  1818. current = next;
  1819. next = &block_buffer[block_index];
  1820. if (current) {
  1821. // Recalculate if current block entry or exit junction speed has changed.
  1822. if (current->recalculate_flag || next->recalculate_flag) {
  1823. // NOTE: Entry and exit factors always > 0 by all previous logic operations.
  1824. calculate_trapezoid_for_block(current, current->entry_speed/current->nominal_speed,
  1825. next->entry_speed/current->nominal_speed);
  1826. current->recalculate_flag = false; // Reset current only to ensure next trapezoid is computed
  1827. }
  1828. }
  1829. block_index = next_block_index( block_index );
  1830. }
  1831. // Last/newest block in buffer. Exit speed is set with MINIMUM_PLANNER_SPEED. Always recalculated.
  1832. if(next != NULL) {
  1833. calculate_trapezoid_for_block(next, next->entry_speed/next->nominal_speed,
  1834. MINIMUM_PLANNER_SPEED/next->nominal_speed);
  1835. next->recalculate_flag = false;
  1836. }
  1837. }
  1838. // Recalculates the motion plan according to the following algorithm:
  1839. //
  1840. // 1. Go over every block in reverse order and calculate a junction speed reduction (i.e. block_t.entry_factor)
  1841. // so that:
  1842. // a. The junction jerk is within the set limit
  1843. // b. No speed reduction within one block requires faster deceleration than the one, true constant
  1844. // acceleration.
  1845. // 2. Go over every block in chronological order and dial down junction speed reduction values if
  1846. // a. The speed increase within one block would require faster accelleration than the one, true
  1847. // constant acceleration.
  1848. //
  1849. // When these stages are complete all blocks have an entry_factor that will allow all speed changes to
  1850. // be performed using only the one, true constant acceleration, and where no junction jerk is jerkier than
  1851. // the set limit. Finally it will:
  1852. //
  1853. // 3. Recalculate trapezoids for all blocks.
  1854. void planner_recalculate() {
  1855. planner_reverse_pass();
  1856. planner_forward_pass();
  1857. planner_recalculate_trapezoids();
  1858. }
  1859. void plan_init() {
  1860. block_buffer_head = 0;
  1861. block_buffer_tail = 0;
  1862. memset(position, 0, sizeof(position)); // clear position
  1863. previous_speed[0] = 0.0;
  1864. previous_speed[1] = 0.0;
  1865. previous_speed[2] = 0.0;
  1866. previous_speed[3] = 0.0;
  1867. previous_nominal_speed = 0.0;
  1868. }
  1869. FORCE_INLINE void plan_discard_current_block() {
  1870. if (block_buffer_head != block_buffer_tail) {
  1871. block_buffer_tail = (block_buffer_tail + 1) & BLOCK_BUFFER_MASK;
  1872. }
  1873. }
  1874. FORCE_INLINE block_t *plan_get_current_block() {
  1875. if (block_buffer_head == block_buffer_tail) {
  1876. return(NULL);
  1877. }
  1878. block_t *block = &block_buffer[block_buffer_tail];
  1879. block->busy = true;
  1880. return(block);
  1881. }
  1882. // Gets the current block. Returns NULL if buffer empty
  1883. FORCE_INLINE bool blocks_queued()
  1884. {
  1885. if (block_buffer_head == block_buffer_tail) {
  1886. return false;
  1887. }
  1888. else
  1889. return true;
  1890. }
  1891. void check_axes_activity() {
  1892. unsigned char x_active = 0;
  1893. unsigned char y_active = 0;
  1894. unsigned char z_active = 0;
  1895. unsigned char e_active = 0;
  1896. block_t *block;
  1897. if(block_buffer_tail != block_buffer_head) {
  1898. uint8_t block_index = block_buffer_tail;
  1899. while(block_index != block_buffer_head) {
  1900. block = &block_buffer[block_index];
  1901. if(block->steps_x != 0) x_active++;
  1902. if(block->steps_y != 0) y_active++;
  1903. if(block->steps_z != 0) z_active++;
  1904. if(block->steps_e != 0) e_active++;
  1905. block_index = (block_index+1) & (BLOCK_BUFFER_SIZE - 1);
  1906. }
  1907. }
  1908. if((DISABLE_X) && (x_active == 0)) disable_x();
  1909. if((DISABLE_Y) && (y_active == 0)) disable_y();
  1910. if((DISABLE_Z) && (z_active == 0)) disable_z();
  1911. if((DISABLE_E) && (e_active == 0)) disable_e();
  1912. }
  1913. float junction_deviation = 0.1;
  1914. // Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in
  1915. // mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration
  1916. // calculation the caller must also provide the physical length of the line in millimeters.
  1917. void plan_buffer_line(float x, float y, float z, float e, float feed_rate)
  1918. {
  1919. // Calculate the buffer head after we push this byte
  1920. int next_buffer_head = next_block_index(block_buffer_head);
  1921. // If the buffer is full: good! That means we are well ahead of the robot.
  1922. // Rest here until there is room in the buffer.
  1923. while(block_buffer_tail == next_buffer_head) {
  1924. manage_heater();
  1925. manage_inactivity(1);
  1926. }
  1927. // The target position of the tool in absolute steps
  1928. // Calculate target position in absolute steps
  1929. //this should be done after the wait, because otherwise a M92 code within the gcode disrupts this calculation somehow
  1930. long target[4];
  1931. target[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]);
  1932. target[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]);
  1933. target[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]);
  1934. target[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]);
  1935. // Prepare to set up new block
  1936. block_t *block = &block_buffer[block_buffer_head];
  1937. // Mark block as not busy (Not executed by the stepper interrupt)
  1938. block->busy = false;
  1939. // Number of steps for each axis
  1940. block->steps_x = labs(target[X_AXIS]-position[X_AXIS]);
  1941. block->steps_y = labs(target[Y_AXIS]-position[Y_AXIS]);
  1942. block->steps_z = labs(target[Z_AXIS]-position[Z_AXIS]);
  1943. block->steps_e = labs(target[E_AXIS]-position[E_AXIS]);
  1944. block->step_event_count = max(block->steps_x, max(block->steps_y, max(block->steps_z, block->steps_e)));
  1945. // Bail if this is a zero-length block
  1946. if (block->step_event_count <=dropsegments) { return; };
  1947. // Compute direction bits for this block
  1948. block->direction_bits = 0;
  1949. if (target[X_AXIS] < position[X_AXIS]) { block->direction_bits |= (1<<X_AXIS); }
  1950. if (target[Y_AXIS] < position[Y_AXIS]) { block->direction_bits |= (1<<Y_AXIS); }
  1951. if (target[Z_AXIS] < position[Z_AXIS]) { block->direction_bits |= (1<<Z_AXIS); }
  1952. if (target[E_AXIS] < position[E_AXIS]) { block->direction_bits |= (1<<E_AXIS); }
  1953. #ifdef DELAY_ENABLE
  1954. if(block->steps_x != 0)
  1955. {
  1956. enable_x();
  1957. delayMicroseconds(DELAY_ENABLE);
  1958. }
  1959. if(block->steps_y != 0)
  1960. {
  1961. enable_y();
  1962. delayMicroseconds(DELAY_ENABLE);
  1963. }
  1964. if(if(block->steps_z != 0))
  1965. {
  1966. enable_z();
  1967. delayMicroseconds(DELAY_ENABLE);
  1968. }
  1969. if(if(block->steps_e != 0))
  1970. {
  1971. enable_e();
  1972. delayMicroseconds(DELAY_ENABLE);
  1973. }
  1974. #else
  1975. //enable active axes
  1976. if(block->steps_x != 0) enable_x();
  1977. if(block->steps_y != 0) enable_y();
  1978. if(block->steps_z != 0) enable_z();
  1979. if(block->steps_e != 0) enable_e();
  1980. #endif
  1981. if (block->steps_e == 0) {
  1982. if(feed_rate<mintravelfeedrate) feed_rate=mintravelfeedrate;
  1983. }
  1984. else {
  1985. if(feed_rate<minimumfeedrate) feed_rate=minimumfeedrate;
  1986. }
  1987. // slow down when de buffer starts to empty, rather than wait at the corner for a buffer refill
  1988. int moves_queued=(block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1);
  1989. #ifdef SLOWDOWN
  1990. if(moves_queued < (BLOCK_BUFFER_SIZE * 0.5) && moves_queued > 1) feed_rate = feed_rate*moves_queued / (BLOCK_BUFFER_SIZE * 0.5);
  1991. #endif
  1992. float delta_mm[4];
  1993. delta_mm[X_AXIS] = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS];
  1994. delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS];
  1995. delta_mm[Z_AXIS] = (target[Z_AXIS]-position[Z_AXIS])/axis_steps_per_unit[Z_AXIS];
  1996. delta_mm[E_AXIS] = (target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS];
  1997. if ( block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0 ) {
  1998. block->millimeters = fabs(delta_mm[E_AXIS]);
  1999. } else {
  2000. block->millimeters = sqrt(square(delta_mm[X_AXIS]) + square(delta_mm[Y_AXIS]) + square(delta_mm[Z_AXIS]));
  2001. }
  2002. float inverse_millimeters = 1.0/block->millimeters; // Inverse millimeters to remove multiple divides
  2003. // Calculate speed in mm/second for each axis. No divide by zero due to previous checks.
  2004. float inverse_second = feed_rate * inverse_millimeters;
  2005. block->nominal_speed = block->millimeters * inverse_second; // (mm/sec) Always > 0
  2006. block->nominal_rate = ceil(block->step_event_count * inverse_second); // (step/sec) Always > 0
  2007. /*
  2008. // segment time im micro seconds
  2009. long segment_time = lround(1000000.0/inverse_second);
  2010. if ((blockcount>0) && (blockcount < (BLOCK_BUFFER_SIZE - 4))) {
  2011. if (segment_time<minsegmenttime) { // buffer is draining, add extra time. The amount of time added increases if the buffer is still emptied more.
  2012. segment_time=segment_time+lround(2*(minsegmenttime-segment_time)/blockcount);
  2013. }
  2014. }
  2015. else {
  2016. if (segment_time<minsegmenttime) segment_time=minsegmenttime;
  2017. }
  2018. // END OF SLOW DOWN SECTION
  2019. */
  2020. // Calculate speed in mm/sec for each axis
  2021. float current_speed[4];
  2022. for(int i=0; i < 4; i++) {
  2023. current_speed[i] = delta_mm[i] * inverse_second;
  2024. }
  2025. // Limit speed per axis
  2026. float speed_factor = 1.0; //factor <=1 do decrease speed
  2027. for(int i=0; i < 4; i++) {
  2028. if(fabs(current_speed[i]) > max_feedrate[i])
  2029. speed_factor = min(speed_factor, max_feedrate[i] / fabs(current_speed[i]));
  2030. }
  2031. // Correct the speed
  2032. if( speed_factor < 1.0) {
  2033. // Serial.print("speed factor : "); Serial.println(speed_factor);
  2034. for(int i=0; i < 4; i++) {
  2035. if(fabs(current_speed[i]) > max_feedrate[i])
  2036. speed_factor = min(speed_factor, max_feedrate[i] / fabs(current_speed[i]));
  2037. /*
  2038. if(speed_factor < 0.1) {
  2039. Serial.print("speed factor : "); Serial.println(speed_factor);
  2040. Serial.print("current_speed"); Serial.print(i); Serial.print(" : "); Serial.println(current_speed[i]);
  2041. }
  2042. */
  2043. }
  2044. for(unsigned char i=0; i < 4; i++) {
  2045. current_speed[i] *= speed_factor;
  2046. }
  2047. block->nominal_speed *= speed_factor;
  2048. block->nominal_rate *= speed_factor;
  2049. }
  2050. // Compute and limit the acceleration rate for the trapezoid generator.
  2051. float steps_per_mm = block->step_event_count/block->millimeters;
  2052. if(block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0) {
  2053. block->acceleration_st = ceil(retract_acceleration * steps_per_mm); // convert to: acceleration steps/sec^2
  2054. }
  2055. else {
  2056. block->acceleration_st = ceil(move_acceleration * steps_per_mm); // convert to: acceleration steps/sec^2
  2057. // Limit acceleration per axis
  2058. if(((float)block->acceleration_st * (float)block->steps_x / (float)block->step_event_count) > axis_steps_per_sqr_second[X_AXIS])
  2059. block->acceleration_st = axis_steps_per_sqr_second[X_AXIS];
  2060. if(((float)block->acceleration_st * (float)block->steps_y / (float)block->step_event_count) > axis_steps_per_sqr_second[Y_AXIS])
  2061. block->acceleration_st = axis_steps_per_sqr_second[Y_AXIS];
  2062. if(((float)block->acceleration_st * (float)block->steps_e / (float)block->step_event_count) > axis_steps_per_sqr_second[E_AXIS])
  2063. block->acceleration_st = axis_steps_per_sqr_second[E_AXIS];
  2064. if(((float)block->acceleration_st * (float)block->steps_z / (float)block->step_event_count ) > axis_steps_per_sqr_second[Z_AXIS])
  2065. block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS];
  2066. }
  2067. block->acceleration = block->acceleration_st / steps_per_mm;
  2068. block->acceleration_rate = (long)((float)block->acceleration_st * 8.388608);
  2069. #if 0 // Use old jerk for now
  2070. // Compute path unit vector
  2071. double unit_vec[3];
  2072. unit_vec[X_AXIS] = delta_mm[X_AXIS]*inverse_millimeters;
  2073. unit_vec[Y_AXIS] = delta_mm[Y_AXIS]*inverse_millimeters;
  2074. unit_vec[Z_AXIS] = delta_mm[Z_AXIS]*inverse_millimeters;
  2075. // Compute maximum allowable entry speed at junction by centripetal acceleration approximation.
  2076. // Let a circle be tangent to both previous and current path line segments, where the junction
  2077. // deviation is defined as the distance from the junction to the closest edge of the circle,
  2078. // colinear with the circle center. The circular segment joining the two paths represents the
  2079. // path of centripetal acceleration. Solve for max velocity based on max acceleration about the
  2080. // radius of the circle, defined indirectly by junction deviation. This may be also viewed as
  2081. // path width or max_jerk in the previous grbl version. This approach does not actually deviate
  2082. // from path, but used as a robust way to compute cornering speeds, as it takes into account the
  2083. // nonlinearities of both the junction angle and junction velocity.
  2084. double vmax_junction = MINIMUM_PLANNER_SPEED; // Set default max junction speed
  2085. // Skip first block or when previous_nominal_speed is used as a flag for homing and offset cycles.
  2086. if ((block_buffer_head != block_buffer_tail) && (previous_nominal_speed > 0.0)) {
  2087. // Compute cosine of angle between previous and current path. (prev_unit_vec is negative)
  2088. // NOTE: Max junction velocity is computed without sin() or acos() by trig half angle identity.
  2089. double cos_theta = - previous_unit_vec[X_AXIS] * unit_vec[X_AXIS]
  2090. - previous_unit_vec[Y_AXIS] * unit_vec[Y_AXIS]
  2091. - previous_unit_vec[Z_AXIS] * unit_vec[Z_AXIS] ;
  2092. // Skip and use default max junction speed for 0 degree acute junction.
  2093. if (cos_theta < 0.95) {
  2094. vmax_junction = min(previous_nominal_speed,block->nominal_speed);
  2095. // Skip and avoid divide by zero for straight junctions at 180 degrees. Limit to min() of nominal speeds.
  2096. if (cos_theta > -0.95) {
  2097. // Compute maximum junction velocity based on maximum acceleration and junction deviation
  2098. double sin_theta_d2 = sqrt(0.5*(1.0-cos_theta)); // Trig half angle identity. Always positive.
  2099. vmax_junction = min(vmax_junction,
  2100. sqrt(block->acceleration * junction_deviation * sin_theta_d2/(1.0-sin_theta_d2)) );
  2101. }
  2102. }
  2103. }
  2104. #endif
  2105. // Start with a safe speed
  2106. float vmax_junction = max_xy_jerk/2;
  2107. if(fabs(current_speed[Z_AXIS]) > max_z_jerk/2)
  2108. vmax_junction = max_z_jerk/2;
  2109. vmax_junction = min(vmax_junction, block->nominal_speed);
  2110. if ((moves_queued > 1) && (previous_nominal_speed > 0.0)) {
  2111. float jerk = sqrt(pow((current_speed[X_AXIS]-previous_speed[X_AXIS]), 2)+pow((current_speed[Y_AXIS]-previous_speed[Y_AXIS]), 2));
  2112. if((previous_speed[X_AXIS] != 0.0) || (previous_speed[Y_AXIS] != 0.0)) {
  2113. vmax_junction = block->nominal_speed;
  2114. }
  2115. if (jerk > max_xy_jerk) {
  2116. vmax_junction *= (max_xy_jerk/jerk);
  2117. }
  2118. if(fabs(current_speed[Z_AXIS] - previous_speed[Z_AXIS]) > max_z_jerk) {
  2119. vmax_junction *= (max_z_jerk/fabs(current_speed[Z_AXIS] - previous_speed[Z_AXIS]));
  2120. }
  2121. }
  2122. block->max_entry_speed = vmax_junction;
  2123. // Initialize block entry speed. Compute based on deceleration to user-defined MINIMUM_PLANNER_SPEED.
  2124. double v_allowable = max_allowable_speed(-block->acceleration,MINIMUM_PLANNER_SPEED,block->millimeters);
  2125. block->entry_speed = min(vmax_junction, v_allowable);
  2126. // Initialize planner efficiency flags
  2127. // Set flag if block will always reach maximum junction speed regardless of entry/exit speeds.
  2128. // If a block can de/ac-celerate from nominal speed to zero within the length of the block, then
  2129. // the current block and next block junction speeds are guaranteed to always be at their maximum
  2130. // junction speeds in deceleration and acceleration, respectively. This is due to how the current
  2131. // block nominal speed limits both the current and next maximum junction speeds. Hence, in both
  2132. // the reverse and forward planners, the corresponding block junction speed will always be at the
  2133. // the maximum junction speed and may always be ignored for any speed reduction checks.
  2134. if (block->nominal_speed <= v_allowable) { block->nominal_length_flag = true; }
  2135. else { block->nominal_length_flag = false; }
  2136. block->recalculate_flag = true; // Always calculate trapezoid for new block
  2137. // Update previous path unit_vector and nominal speed
  2138. memcpy(previous_speed, current_speed, sizeof(previous_speed)); // previous_speed[] = current_speed[]
  2139. previous_nominal_speed = block->nominal_speed;
  2140. #ifdef ADVANCE
  2141. // Calculate advance rate
  2142. if((block->steps_e == 0) || (block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0)) {
  2143. block->advance_rate = 0;
  2144. block->advance = 0;
  2145. }
  2146. else {
  2147. long acc_dist = estimate_acceleration_distance(0, block->nominal_rate, block->acceleration_st);
  2148. float advance = (STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K) *
  2149. (current_speed[E_AXIS] * current_speed[E_AXIS] * EXTRUTION_AREA * EXTRUTION_AREA)*256;
  2150. block->advance = advance;
  2151. if(acc_dist == 0) {
  2152. block->advance_rate = 0;
  2153. }
  2154. else {
  2155. block->advance_rate = advance / (float)acc_dist;
  2156. }
  2157. }
  2158. #endif // ADVANCE
  2159. calculate_trapezoid_for_block(block, block->entry_speed/block->nominal_speed,
  2160. MINIMUM_PLANNER_SPEED/block->nominal_speed);
  2161. // Move buffer head
  2162. block_buffer_head = next_buffer_head;
  2163. // Update position
  2164. memcpy(position, target, sizeof(target)); // position[] = target[]
  2165. planner_recalculate();
  2166. #ifdef AUTOTEMP
  2167. getHighESpeed();
  2168. #endif
  2169. st_wake_up();
  2170. }
  2171. void plan_set_position(float x, float y, float z, float e)
  2172. {
  2173. position[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]);
  2174. position[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]);
  2175. position[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]);
  2176. position[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]);
  2177. previous_nominal_speed = 0.0; // Resets planner junction speeds. Assumes start from rest.
  2178. previous_speed[0] = 0.0;
  2179. previous_speed[1] = 0.0;
  2180. previous_speed[2] = 0.0;
  2181. previous_speed[3] = 0.0;
  2182. }
  2183. #ifdef AUTOTEMP
  2184. void getHighESpeed()
  2185. {
  2186. static float oldt=0;
  2187. if(!autotemp_enabled)
  2188. return;
  2189. if((target_temp+2) < autotemp_min) //probably temperature set to zero.
  2190. return; //do nothing
  2191. float high=0;
  2192. uint8_t block_index = block_buffer_tail;
  2193. while(block_index != block_buffer_head)
  2194. {
  2195. float se=block_buffer[block_index].steps_e/float(block_buffer[block_index].step_event_count)*block_buffer[block_index].nominal_rate;
  2196. //se; units steps/sec;
  2197. if(se>high)
  2198. {
  2199. high=se;
  2200. }
  2201. block_index = (block_index+1) & (BLOCK_BUFFER_SIZE - 1);
  2202. }
  2203. float t=autotemp_min+high*autotemp_factor;
  2204. if(t<autotemp_min)
  2205. t=autotemp_min;
  2206. if(t>autotemp_max)
  2207. t=autotemp_max;
  2208. if(oldt>t)
  2209. {
  2210. t=AUTOTEMP_OLDWEIGHT*oldt+(1-AUTOTEMP_OLDWEIGHT)*t;
  2211. }
  2212. oldt=t;
  2213. autotemp_setpoint = (int)t;
  2214. }
  2215. #endif
  2216. // Stepper
  2217. // intRes = intIn1 * intIn2 >> 16
  2218. // uses:
  2219. // r26 to store 0
  2220. // r27 to store the byte 1 of the 24 bit result
  2221. #define MultiU16X8toH16(intRes, charIn1, intIn2) \
  2222. asm volatile ( \
  2223. "clr r26 \n\t" \
  2224. "mul %A1, %B2 \n\t" \
  2225. "movw %A0, r0 \n\t" \
  2226. "mul %A1, %A2 \n\t" \
  2227. "add %A0, r1 \n\t" \
  2228. "adc %B0, r26 \n\t" \
  2229. "lsr r0 \n\t" \
  2230. "adc %A0, r26 \n\t" \
  2231. "adc %B0, r26 \n\t" \
  2232. "clr r1 \n\t" \
  2233. : \
  2234. "=&r" (intRes) \
  2235. : \
  2236. "d" (charIn1), \
  2237. "d" (intIn2) \
  2238. : \
  2239. "r26" \
  2240. )
  2241. // intRes = longIn1 * longIn2 >> 24
  2242. // uses:
  2243. // r26 to store 0
  2244. // r27 to store the byte 1 of the 48bit result
  2245. #define MultiU24X24toH16(intRes, longIn1, longIn2) \
  2246. asm volatile ( \
  2247. "clr r26 \n\t" \
  2248. "mul %A1, %B2 \n\t" \
  2249. "mov r27, r1 \n\t" \
  2250. "mul %B1, %C2 \n\t" \
  2251. "movw %A0, r0 \n\t" \
  2252. "mul %C1, %C2 \n\t" \
  2253. "add %B0, r0 \n\t" \
  2254. "mul %C1, %B2 \n\t" \
  2255. "add %A0, r0 \n\t" \
  2256. "adc %B0, r1 \n\t" \
  2257. "mul %A1, %C2 \n\t" \
  2258. "add r27, r0 \n\t" \
  2259. "adc %A0, r1 \n\t" \
  2260. "adc %B0, r26 \n\t" \
  2261. "mul %B1, %B2 \n\t" \
  2262. "add r27, r0 \n\t" \
  2263. "adc %A0, r1 \n\t" \
  2264. "adc %B0, r26 \n\t" \
  2265. "mul %C1, %A2 \n\t" \
  2266. "add r27, r0 \n\t" \
  2267. "adc %A0, r1 \n\t" \
  2268. "adc %B0, r26 \n\t" \
  2269. "mul %B1, %A2 \n\t" \
  2270. "add r27, r1 \n\t" \
  2271. "adc %A0, r26 \n\t" \
  2272. "adc %B0, r26 \n\t" \
  2273. "lsr r27 \n\t" \
  2274. "adc %A0, r26 \n\t" \
  2275. "adc %B0, r26 \n\t" \
  2276. "clr r1 \n\t" \
  2277. : \
  2278. "=&r" (intRes) \
  2279. : \
  2280. "d" (longIn1), \
  2281. "d" (longIn2) \
  2282. : \
  2283. "r26" , "r27" \
  2284. )
  2285. // Some useful constants
  2286. #define ENABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 |= (1<<OCIE1A)
  2287. #define DISABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 &= ~(1<<OCIE1A)
  2288. #ifdef ENDSTOPS_ONLY_FOR_HOMING
  2289. #define CHECK_ENDSTOPS if(check_endstops)
  2290. #else
  2291. #define CHECK_ENDSTOPS
  2292. #endif
  2293. static block_t *current_block; // A pointer to the block currently being traced
  2294. // Variables used by The Stepper Driver Interrupt
  2295. static unsigned char out_bits; // The next stepping-bits to be output
  2296. static long counter_x, // Counter variables for the bresenham line tracer
  2297. counter_y,
  2298. counter_z,
  2299. counter_e;
  2300. static unsigned long step_events_completed; // The number of step events executed in the current block
  2301. #ifdef ADVANCE
  2302. static long advance_rate, advance, final_advance = 0;
  2303. static short old_advance = 0;
  2304. #endif
  2305. static short e_steps;
  2306. static unsigned char busy = false; // TRUE when SIG_OUTPUT_COMPARE1A is being serviced. Used to avoid retriggering that handler.
  2307. static long acceleration_time, deceleration_time;
  2308. static unsigned short acc_step_rate; // needed for deccelaration start point
  2309. static char step_loops;
  2310. static unsigned short OCR1A_nominal;
  2311. static volatile bool endstop_x_hit=false;
  2312. static volatile bool endstop_y_hit=false;
  2313. static volatile bool endstop_z_hit=false;
  2314. static bool old_x_min_endstop=false;
  2315. static bool old_x_max_endstop=false;
  2316. static bool old_y_min_endstop=false;
  2317. static bool old_y_max_endstop=false;
  2318. static bool old_z_min_endstop=false;
  2319. static bool old_z_max_endstop=false;
  2320. // __________________________
  2321. // /| |\ _________________ ^
  2322. // / | | \ /| |\ |
  2323. // / | | \ / | | \ s
  2324. // / | | | | | \ p
  2325. // / | | | | | \ e
  2326. // +-----+------------------------+---+--+---------------+----+ e
  2327. // | BLOCK 1 | BLOCK 2 | d
  2328. //
  2329. // time ----->
  2330. //
  2331. // The trapezoid is the shape the speed curve over time. It starts at block->initial_rate, accelerates
  2332. // first block->accelerate_until step_events_completed, then keeps going at constant speed until
  2333. // step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset.
  2334. // The slope of acceleration is calculated with the leib ramp alghorithm.
  2335. void st_wake_up()
  2336. {
  2337. // TCNT1 = 0;
  2338. if(busy == false)
  2339. ENABLE_STEPPER_DRIVER_INTERRUPT();
  2340. }
  2341. FORCE_INLINE unsigned short calc_timer(unsigned short step_rate)
  2342. {
  2343. unsigned short timer;
  2344. if(step_rate > MAX_STEP_FREQUENCY) step_rate = MAX_STEP_FREQUENCY;
  2345. if(step_rate > 20000) { // If steprate > 20kHz >> step 4 times
  2346. step_rate = (step_rate >> 2)&0x3fff;
  2347. step_loops = 4;
  2348. }
  2349. else if(step_rate > 10000) { // If steprate > 10kHz >> step 2 times
  2350. step_rate = (step_rate >> 1)&0x7fff;
  2351. step_loops = 2;
  2352. }
  2353. else {
  2354. step_loops = 1;
  2355. }
  2356. if(step_rate < (F_CPU/500000)) step_rate = (F_CPU/500000);
  2357. step_rate -= (F_CPU/500000); // Correct for minimal speed
  2358. if(step_rate >= (8*256)) // higher step rate
  2359. { // higher step rate
  2360. unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate>>8)][0];
  2361. unsigned char tmp_step_rate = (step_rate & 0x00ff);
  2362. unsigned short gain = (unsigned short)pgm_read_word_near(table_address+2);
  2363. MultiU16X8toH16(timer, tmp_step_rate, gain);
  2364. timer = (unsigned short)pgm_read_word_near(table_address) - timer;
  2365. }
  2366. else
  2367. { // lower step rates
  2368. unsigned short table_address = (unsigned short)&speed_lookuptable_slow[0][0];
  2369. table_address += ((step_rate)>>1) & 0xfffc;
  2370. timer = (unsigned short)pgm_read_word_near(table_address);
  2371. timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
  2372. }
  2373. if(timer < 100) { timer = 100; }//(20kHz this should never happen)
  2374. return timer;
  2375. }
  2376. // Initializes the trapezoid generator from the current block. Called whenever a new
  2377. // block begins.
  2378. FORCE_INLINE void trapezoid_generator_reset()
  2379. {
  2380. #ifdef ADVANCE
  2381. advance = current_block->initial_advance;
  2382. final_advance = current_block->final_advance;
  2383. // Do E steps + advance steps
  2384. e_steps += ((advance >>8) - old_advance);
  2385. old_advance = advance >>8;
  2386. #endif
  2387. deceleration_time = 0;
  2388. // step_rate to timer interval
  2389. acc_step_rate = current_block->initial_rate;
  2390. acceleration_time = calc_timer(acc_step_rate);
  2391. OCR1A = acceleration_time;
  2392. OCR1A_nominal = calc_timer(current_block->nominal_rate);
  2393. }
  2394. // "The Stepper Driver Interrupt" - This timer interrupt is the workhorse.
  2395. // It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately.
  2396. ISR(TIMER1_COMPA_vect)
  2397. {
  2398. // If there is no current block, attempt to pop one from the buffer
  2399. if (current_block == NULL) {
  2400. // Anything in the buffer?
  2401. current_block = plan_get_current_block();
  2402. if (current_block != NULL) {
  2403. trapezoid_generator_reset();
  2404. counter_x = -(current_block->step_event_count >> 1);
  2405. counter_y = counter_x;
  2406. counter_z = counter_x;
  2407. counter_e = counter_x;
  2408. step_events_completed = 0;
  2409. // #ifdef ADVANCE
  2410. // e_steps = 0;
  2411. // #endif
  2412. }
  2413. else {
  2414. OCR1A=2000; // 1kHz.
  2415. }
  2416. }
  2417. if (current_block != NULL) {
  2418. // Set directions TO DO This should be done once during init of trapezoid. Endstops -> interrupt
  2419. out_bits = current_block->direction_bits;
  2420. // Set direction en check limit switches
  2421. if ((out_bits & (1<<X_AXIS)) != 0) { // -direction
  2422. WRITE(X_DIR_PIN, INVERT_X_DIR);
  2423. CHECK_ENDSTOPS
  2424. {
  2425. #if X_MIN_PIN > -1
  2426. bool x_min_endstop=(READ(X_MIN_PIN) != X_ENDSTOP_INVERT);
  2427. if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
  2428. endstop_x_hit=true;
  2429. step_events_completed = current_block->step_event_count;
  2430. }
  2431. old_x_min_endstop = x_min_endstop;
  2432. #endif
  2433. }
  2434. }
  2435. else { // +direction
  2436. WRITE(X_DIR_PIN,!INVERT_X_DIR);
  2437. CHECK_ENDSTOPS
  2438. {
  2439. #if X_MAX_PIN > -1
  2440. bool x_max_endstop=(READ(X_MAX_PIN) != X_ENDSTOP_INVERT);
  2441. if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
  2442. endstop_x_hit=true;
  2443. step_events_completed = current_block->step_event_count;
  2444. }
  2445. old_x_max_endstop = x_max_endstop;
  2446. #endif
  2447. }
  2448. }
  2449. if ((out_bits & (1<<Y_AXIS)) != 0) { // -direction
  2450. WRITE(Y_DIR_PIN,INVERT_Y_DIR);
  2451. CHECK_ENDSTOPS
  2452. {
  2453. #if Y_MIN_PIN > -1
  2454. bool y_min_endstop=(READ(Y_MIN_PIN) != Y_ENDSTOP_INVERT);
  2455. if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
  2456. endstop_y_hit=true;
  2457. step_events_completed = current_block->step_event_count;
  2458. }
  2459. old_y_min_endstop = y_min_endstop;
  2460. #endif
  2461. }
  2462. }
  2463. else { // +direction
  2464. WRITE(Y_DIR_PIN,!INVERT_Y_DIR);
  2465. CHECK_ENDSTOPS
  2466. {
  2467. #if Y_MAX_PIN > -1
  2468. bool y_max_endstop=(READ(Y_MAX_PIN) != Y_ENDSTOP_INVERT);
  2469. if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
  2470. endstop_y_hit=true;
  2471. step_events_completed = current_block->step_event_count;
  2472. }
  2473. old_y_max_endstop = y_max_endstop;
  2474. #endif
  2475. }
  2476. }
  2477. if ((out_bits & (1<<Z_AXIS)) != 0) { // -direction
  2478. WRITE(Z_DIR_PIN,INVERT_Z_DIR);
  2479. CHECK_ENDSTOPS
  2480. {
  2481. #if Z_MIN_PIN > -1
  2482. bool z_min_endstop=(READ(Z_MIN_PIN) != Z_ENDSTOP_INVERT);
  2483. if(z_min_endstop && old_z_min_endstop && (current_block->steps_z > 0)) {
  2484. endstop_z_hit=true;
  2485. step_events_completed = current_block->step_event_count;
  2486. }
  2487. old_z_min_endstop = z_min_endstop;
  2488. #endif
  2489. }
  2490. }
  2491. else { // +direction
  2492. WRITE(Z_DIR_PIN,!INVERT_Z_DIR);
  2493. CHECK_ENDSTOPS
  2494. {
  2495. #if Z_MAX_PIN > -1
  2496. bool z_max_endstop=(READ(Z_MAX_PIN) != Z_ENDSTOP_INVERT);
  2497. if(z_max_endstop && old_z_max_endstop && (current_block->steps_z > 0)) {
  2498. endstop_z_hit=true;
  2499. step_events_completed = current_block->step_event_count;
  2500. }
  2501. old_z_max_endstop = z_max_endstop;
  2502. #endif
  2503. }
  2504. }
  2505. #ifndef ADVANCE
  2506. if ((out_bits & (1<<E_AXIS)) != 0) { // -direction
  2507. WRITE(E_DIR_PIN,INVERT_E_DIR);
  2508. }
  2509. else { // +direction
  2510. WRITE(E_DIR_PIN,!INVERT_E_DIR);
  2511. }
  2512. #endif //!ADVANCE
  2513. for(int8_t i=0; i < step_loops; i++) { // Take multiple steps per interrupt (For high speed moves)
  2514. #ifdef ADVANCE
  2515. counter_e += current_block->steps_e;
  2516. if (counter_e > 0) {
  2517. counter_e -= current_block->step_event_count;
  2518. if ((out_bits & (1<<E_AXIS)) != 0) { // - direction
  2519. e_steps--;
  2520. }
  2521. else {
  2522. e_steps++;
  2523. }
  2524. }
  2525. #endif //ADVANCE
  2526. counter_x += current_block->steps_x;
  2527. if (counter_x > 0) {
  2528. WRITE(X_STEP_PIN, HIGH);
  2529. counter_x -= current_block->step_event_count;
  2530. WRITE(X_STEP_PIN, LOW);
  2531. }
  2532. counter_y += current_block->steps_y;
  2533. if (counter_y > 0) {
  2534. WRITE(Y_STEP_PIN, HIGH);
  2535. counter_y -= current_block->step_event_count;
  2536. WRITE(Y_STEP_PIN, LOW);
  2537. }
  2538. counter_z += current_block->steps_z;
  2539. if (counter_z > 0) {
  2540. WRITE(Z_STEP_PIN, HIGH);
  2541. counter_z -= current_block->step_event_count;
  2542. WRITE(Z_STEP_PIN, LOW);
  2543. }
  2544. #ifndef ADVANCE
  2545. counter_e += current_block->steps_e;
  2546. if (counter_e > 0) {
  2547. WRITE(E_STEP_PIN, HIGH);
  2548. counter_e -= current_block->step_event_count;
  2549. WRITE(E_STEP_PIN, LOW);
  2550. }
  2551. #endif //!ADVANCE
  2552. step_events_completed += 1;
  2553. if(step_events_completed >= current_block->step_event_count) break;
  2554. }
  2555. // Calculare new timer value
  2556. unsigned short timer;
  2557. unsigned short step_rate;
  2558. if (step_events_completed <= (unsigned long int)current_block->accelerate_until) {
  2559. MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
  2560. acc_step_rate += current_block->initial_rate;
  2561. // upper limit
  2562. if(acc_step_rate > current_block->nominal_rate)
  2563. acc_step_rate = current_block->nominal_rate;
  2564. // step_rate to timer interval
  2565. timer = calc_timer(acc_step_rate);
  2566. OCR1A = timer;
  2567. acceleration_time += timer;
  2568. #ifdef ADVANCE
  2569. for(int8_t i=0; i < step_loops; i++) {
  2570. advance += advance_rate;
  2571. }
  2572. //if(advance > current_block->advance) advance = current_block->advance;
  2573. // Do E steps + advance steps
  2574. e_steps += ((advance >>8) - old_advance);
  2575. old_advance = advance >>8;
  2576. #endif
  2577. }
  2578. else if (step_events_completed > (unsigned long int)current_block->decelerate_after) {
  2579. MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate);
  2580. if(step_rate > acc_step_rate) { // Check step_rate stays positive
  2581. step_rate = current_block->final_rate;
  2582. }
  2583. else {
  2584. step_rate = acc_step_rate - step_rate; // Decelerate from aceleration end point.
  2585. }
  2586. // lower limit
  2587. if(step_rate < current_block->final_rate)
  2588. step_rate = current_block->final_rate;
  2589. // step_rate to timer interval
  2590. timer = calc_timer(step_rate);
  2591. OCR1A = timer;
  2592. deceleration_time += timer;
  2593. #ifdef ADVANCE
  2594. for(int8_t i=0; i < step_loops; i++) {
  2595. advance -= advance_rate;
  2596. }
  2597. if(advance < final_advance) advance = final_advance;
  2598. // Do E steps + advance steps
  2599. e_steps += ((advance >>8) - old_advance);
  2600. old_advance = advance >>8;
  2601. #endif //ADVANCE
  2602. }
  2603. else {
  2604. OCR1A = OCR1A_nominal;
  2605. }
  2606. // If current block is finished, reset pointer
  2607. if (step_events_completed >= current_block->step_event_count) {
  2608. current_block = NULL;
  2609. plan_discard_current_block();
  2610. }
  2611. }
  2612. }
  2613. #ifdef ADVANCE
  2614. unsigned char old_OCR0A;
  2615. // Timer interrupt for E. e_steps is set in the main routine;
  2616. // Timer 0 is shared with millies
  2617. ISR(TIMER0_COMPA_vect)
  2618. {
  2619. old_OCR0A += 52; // ~10kHz interrupt (250000 / 26 = 9615kHz)
  2620. OCR0A = old_OCR0A;
  2621. // Set E direction (Depends on E direction + advance)
  2622. for(unsigned char i=0; i<4;i++)
  2623. {
  2624. if (e_steps != 0)
  2625. {
  2626. WRITE(E0_STEP_PIN, LOW);
  2627. if (e_steps < 0) {
  2628. WRITE(E0_DIR_PIN, INVERT_E0_DIR);
  2629. e_steps++;
  2630. WRITE(E0_STEP_PIN, HIGH);
  2631. }
  2632. else if (e_steps > 0) {
  2633. WRITE(E0_DIR_PIN, !INVERT_E0_DIR);
  2634. e_steps--;
  2635. WRITE(E0_STEP_PIN, HIGH);
  2636. }
  2637. }
  2638. }
  2639. }
  2640. #endif // ADVANCE
  2641. void st_init()
  2642. {
  2643. // waveform generation = 0100 = CTC
  2644. TCCR1B &= ~(1<<WGM13);
  2645. TCCR1B |= (1<<WGM12);
  2646. TCCR1A &= ~(1<<WGM11);
  2647. TCCR1A &= ~(1<<WGM10);
  2648. // output mode = 00 (disconnected)
  2649. TCCR1A &= ~(3<<COM1A0);
  2650. TCCR1A &= ~(3<<COM1B0);
  2651. // Set the timer pre-scaler
  2652. // Generally we use a divider of 8, resulting in a 2MHz timer
  2653. // frequency on a 16MHz MCU. If you are going to change this, be
  2654. // sure to regenerate speed_lookuptable.h with
  2655. // create_speed_lookuptable.py
  2656. TCCR1B = (TCCR1B & ~(0x07<<CS10)) | (2<<CS10); // 2MHz timer
  2657. OCR1A = 0x4000;
  2658. TCNT1 = 0;
  2659. ENABLE_STEPPER_DRIVER_INTERRUPT();
  2660. #ifdef ADVANCE
  2661. #if defined(TCCR0A) && defined(WGM01)
  2662. TCCR0A &= ~(1<<WGM01);
  2663. TCCR0A &= ~(1<<WGM00);
  2664. #endif
  2665. e_steps = 0;
  2666. TIMSK0 |= (1<<OCIE0A);
  2667. #endif //ADVANCE
  2668. #ifdef ENDSTOPS_ONLY_FOR_HOMING
  2669. enable_endstops(false);
  2670. #else
  2671. enable_endstops(true);
  2672. #endif
  2673. sei();
  2674. }
  2675. // Block until all buffered steps are executed
  2676. void st_synchronize()
  2677. {
  2678. while(blocks_queued()) {
  2679. manage_heater();
  2680. manage_inactivity(1);
  2681. }
  2682. }
  2683. #ifdef DEBUG
  2684. void log_message(char* message) {
  2685. Serial.print("DEBUG"); Serial.println(message);
  2686. }
  2687. void log_bool(char* message, bool value) {
  2688. Serial.print("DEBUG"); Serial.print(message); Serial.print(": "); Serial.println(value);
  2689. }
  2690. void log_int(char* message, int value) {
  2691. Serial.print("DEBUG"); Serial.print(message); Serial.print(": "); Serial.println(value);
  2692. }
  2693. void log_long(char* message, long value) {
  2694. Serial.print("DEBUG"); Serial.print(message); Serial.print(": "); Serial.println(value);
  2695. }
  2696. void log_float(char* message, float value) {
  2697. Serial.print("DEBUG"); Serial.print(message); Serial.print(": "); Serial.println(value);
  2698. }
  2699. void log_uint(char* message, unsigned int value) {
  2700. Serial.print("DEBUG"); Serial.print(message); Serial.print(": "); Serial.println(value);
  2701. }
  2702. void log_ulong(char* message, unsigned long value) {
  2703. Serial.print("DEBUG"); Serial.print(message); Serial.print(": "); Serial.println(value);
  2704. }
  2705. void log_int_array(char* message, int value[], int array_lenght) {
  2706. Serial.print("DEBUG"); Serial.print(message); Serial.print(": {");
  2707. for(int i=0; i < array_lenght; i++){
  2708. Serial.print(value[i]);
  2709. if(i != array_lenght-1) Serial.print(", ");
  2710. }
  2711. Serial.println("}");
  2712. }
  2713. void log_long_array(char* message, long value[], int array_lenght) {
  2714. Serial.print("DEBUG"); Serial.print(message); Serial.print(": {");
  2715. for(int i=0; i < array_lenght; i++){
  2716. Serial.print(value[i]);
  2717. if(i != array_lenght-1) Serial.print(", ");
  2718. }
  2719. Serial.println("}");
  2720. }
  2721. void log_float_array(char* message, float value[], int array_lenght) {
  2722. Serial.print("DEBUG"); Serial.print(message); Serial.print(": {");
  2723. for(int i=0; i < array_lenght; i++){
  2724. Serial.print(value[i]);
  2725. if(i != array_lenght-1) Serial.print(", ");
  2726. }
  2727. Serial.println("}");
  2728. }
  2729. void log_uint_array(char* message, unsigned int value[], int array_lenght) {
  2730. Serial.print("DEBUG"); Serial.print(message); Serial.print(": {");
  2731. for(int i=0; i < array_lenght; i++){
  2732. Serial.print(value[i]);
  2733. if(i != array_lenght-1) Serial.print(", ");
  2734. }
  2735. Serial.println("}");
  2736. }
  2737. void log_ulong_array(char* message, unsigned long value[], int array_lenght) {
  2738. Serial.print("DEBUG"); Serial.print(message); Serial.print(": {");
  2739. for(int i=0; i < array_lenght; i++){
  2740. Serial.print(value[i]);
  2741. if(i != array_lenght-1) Serial.print(", ");
  2742. }
  2743. Serial.println("}");
  2744. }
  2745. #endif