Marlin_main.cpp 166 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812181318141815181618171818181918201821182218231824182518261827182818291830183118321833183418351836183718381839184018411842184318441845184618471848184918501851185218531854185518561857185818591860186118621863186418651866186718681869187018711872187318741875187618771878187918801881188218831884188518861887188818891890189118921893189418951896189718981899190019011902190319041905190619071908190919101911191219131914191519161917191819191920192119221923192419251926192719281929193019311932193319341935193619371938193919401941194219431944194519461947194819491950195119521953195419551956195719581959196019611962196319641965196619671968196919701971197219731974197519761977197819791980198119821983198419851986198719881989199019911992199319941995199619971998199920002001200220032004200520062007200820092010201120122013201420152016201720182019202020212022202320242025202620272028202920302031203220332034203520362037203820392040204120422043204420452046204720482049205020512052205320542055205620572058205920602061206220632064206520662067206820692070207120722073207420752076207720782079208020812082208320842085208620872088208920902091209220932094209520962097209820992100210121022103210421052106210721082109211021112112211321142115211621172118211921202121212221232124212521262127212821292130213121322133213421352136213721382139214021412142214321442145214621472148214921502151215221532154215521562157215821592160216121622163216421652166216721682169217021712172217321742175217621772178217921802181218221832184218521862187218821892190219121922193219421952196219721982199220022012202220322042205220622072208220922102211221222132214221522162217221822192220222122222223222422252226222722282229223022312232223322342235223622372238223922402241224222432244224522462247224822492250225122522253225422552256225722582259226022612262226322642265226622672268226922702271227222732274227522762277227822792280228122822283228422852286228722882289229022912292229322942295229622972298229923002301230223032304230523062307230823092310231123122313231423152316231723182319232023212322232323242325232623272328232923302331233223332334233523362337233823392340234123422343234423452346234723482349235023512352235323542355235623572358235923602361236223632364236523662367236823692370237123722373237423752376237723782379238023812382238323842385238623872388238923902391239223932394239523962397239823992400240124022403240424052406240724082409241024112412241324142415241624172418241924202421242224232424242524262427242824292430243124322433243424352436243724382439244024412442244324442445244624472448244924502451245224532454245524562457245824592460246124622463246424652466246724682469247024712472247324742475247624772478247924802481248224832484248524862487248824892490249124922493249424952496249724982499250025012502250325042505250625072508250925102511251225132514251525162517251825192520252125222523252425252526252725282529253025312532253325342535253625372538253925402541254225432544254525462547254825492550255125522553255425552556255725582559256025612562256325642565256625672568256925702571257225732574257525762577257825792580258125822583258425852586258725882589259025912592259325942595259625972598259926002601260226032604260526062607260826092610261126122613261426152616261726182619262026212622262326242625262626272628262926302631263226332634263526362637263826392640264126422643264426452646264726482649265026512652265326542655265626572658265926602661266226632664266526662667266826692670267126722673267426752676267726782679268026812682268326842685268626872688268926902691269226932694269526962697269826992700270127022703270427052706270727082709271027112712271327142715271627172718271927202721272227232724272527262727272827292730273127322733273427352736273727382739274027412742274327442745274627472748274927502751275227532754275527562757275827592760276127622763276427652766276727682769277027712772277327742775277627772778277927802781278227832784278527862787278827892790279127922793279427952796279727982799280028012802280328042805280628072808280928102811281228132814281528162817281828192820282128222823282428252826282728282829283028312832283328342835283628372838283928402841284228432844284528462847284828492850285128522853285428552856285728582859286028612862286328642865286628672868286928702871287228732874287528762877287828792880288128822883288428852886288728882889289028912892289328942895289628972898289929002901290229032904290529062907290829092910291129122913291429152916291729182919292029212922292329242925292629272928292929302931293229332934293529362937293829392940294129422943294429452946294729482949295029512952295329542955295629572958295929602961296229632964296529662967296829692970297129722973297429752976297729782979298029812982298329842985298629872988298929902991299229932994299529962997299829993000300130023003300430053006300730083009301030113012301330143015301630173018301930203021302230233024302530263027302830293030303130323033303430353036303730383039304030413042304330443045304630473048304930503051305230533054305530563057305830593060306130623063306430653066306730683069307030713072307330743075307630773078307930803081308230833084308530863087308830893090309130923093309430953096309730983099310031013102310331043105310631073108310931103111311231133114311531163117311831193120312131223123312431253126312731283129313031313132313331343135313631373138313931403141314231433144314531463147314831493150315131523153315431553156315731583159316031613162316331643165316631673168316931703171317231733174317531763177317831793180318131823183318431853186318731883189319031913192319331943195319631973198319932003201320232033204320532063207320832093210321132123213321432153216321732183219322032213222322332243225322632273228322932303231323232333234323532363237323832393240324132423243324432453246324732483249325032513252325332543255325632573258325932603261326232633264326532663267326832693270327132723273327432753276327732783279328032813282328332843285328632873288328932903291329232933294329532963297329832993300330133023303330433053306330733083309331033113312331333143315331633173318331933203321332233233324332533263327332833293330333133323333333433353336333733383339334033413342334333443345334633473348334933503351335233533354335533563357335833593360336133623363336433653366336733683369337033713372337333743375337633773378337933803381338233833384338533863387338833893390339133923393339433953396339733983399340034013402340334043405340634073408340934103411341234133414341534163417341834193420342134223423342434253426342734283429343034313432343334343435343634373438343934403441344234433444344534463447344834493450345134523453345434553456345734583459346034613462346334643465346634673468346934703471347234733474347534763477347834793480348134823483348434853486348734883489349034913492349334943495349634973498349935003501350235033504350535063507350835093510351135123513351435153516351735183519352035213522352335243525352635273528352935303531353235333534353535363537353835393540354135423543354435453546354735483549355035513552355335543555355635573558355935603561356235633564356535663567356835693570357135723573357435753576357735783579358035813582358335843585358635873588358935903591359235933594359535963597359835993600360136023603360436053606360736083609361036113612361336143615361636173618361936203621362236233624362536263627362836293630363136323633363436353636363736383639364036413642364336443645364636473648364936503651365236533654365536563657365836593660366136623663366436653666366736683669367036713672367336743675367636773678367936803681368236833684368536863687368836893690369136923693369436953696369736983699370037013702370337043705370637073708370937103711371237133714371537163717371837193720372137223723372437253726372737283729373037313732373337343735373637373738373937403741374237433744374537463747374837493750375137523753375437553756375737583759376037613762376337643765376637673768376937703771377237733774377537763777377837793780378137823783378437853786378737883789379037913792379337943795379637973798379938003801380238033804380538063807380838093810381138123813381438153816381738183819382038213822382338243825382638273828382938303831383238333834383538363837383838393840384138423843384438453846384738483849385038513852385338543855385638573858385938603861386238633864386538663867386838693870387138723873387438753876387738783879388038813882388338843885388638873888388938903891389238933894389538963897389838993900390139023903390439053906390739083909391039113912391339143915391639173918391939203921392239233924392539263927392839293930393139323933393439353936393739383939394039413942394339443945394639473948394939503951395239533954395539563957395839593960396139623963396439653966396739683969397039713972397339743975397639773978397939803981398239833984398539863987398839893990399139923993399439953996399739983999400040014002400340044005400640074008400940104011401240134014401540164017401840194020402140224023402440254026402740284029403040314032403340344035403640374038403940404041404240434044404540464047404840494050405140524053405440554056405740584059406040614062406340644065406640674068406940704071407240734074407540764077407840794080408140824083408440854086408740884089409040914092409340944095409640974098409941004101410241034104410541064107410841094110411141124113411441154116411741184119412041214122412341244125412641274128412941304131413241334134413541364137413841394140414141424143414441454146414741484149415041514152415341544155415641574158415941604161416241634164416541664167416841694170417141724173417441754176417741784179418041814182418341844185418641874188418941904191419241934194419541964197419841994200420142024203420442054206420742084209421042114212421342144215421642174218421942204221422242234224422542264227422842294230423142324233423442354236423742384239424042414242424342444245424642474248424942504251425242534254425542564257425842594260426142624263426442654266426742684269427042714272427342744275427642774278427942804281428242834284428542864287428842894290429142924293429442954296429742984299430043014302430343044305430643074308430943104311431243134314431543164317431843194320432143224323432443254326432743284329433043314332433343344335433643374338433943404341434243434344434543464347434843494350435143524353435443554356435743584359436043614362436343644365436643674368436943704371437243734374437543764377437843794380438143824383438443854386438743884389439043914392439343944395439643974398439944004401440244034404440544064407440844094410441144124413441444154416441744184419442044214422442344244425442644274428442944304431443244334434443544364437443844394440444144424443444444454446444744484449445044514452445344544455445644574458445944604461446244634464446544664467446844694470447144724473447444754476447744784479448044814482448344844485448644874488448944904491449244934494449544964497449844994500450145024503450445054506450745084509451045114512451345144515451645174518451945204521452245234524452545264527452845294530453145324533453445354536453745384539454045414542454345444545454645474548454945504551455245534554455545564557455845594560456145624563456445654566456745684569457045714572457345744575457645774578457945804581458245834584458545864587458845894590459145924593459445954596459745984599460046014602460346044605460646074608460946104611461246134614461546164617461846194620462146224623462446254626462746284629463046314632463346344635463646374638463946404641464246434644464546464647464846494650465146524653465446554656465746584659466046614662466346644665466646674668466946704671467246734674467546764677467846794680468146824683468446854686468746884689469046914692469346944695469646974698469947004701470247034704470547064707470847094710471147124713471447154716471747184719472047214722472347244725472647274728472947304731473247334734473547364737473847394740474147424743474447454746474747484749475047514752475347544755475647574758475947604761476247634764476547664767476847694770477147724773477447754776477747784779478047814782478347844785478647874788478947904791479247934794479547964797479847994800480148024803480448054806480748084809481048114812481348144815481648174818481948204821482248234824482548264827482848294830483148324833483448354836483748384839484048414842484348444845484648474848484948504851485248534854485548564857485848594860486148624863486448654866486748684869487048714872487348744875487648774878487948804881488248834884488548864887488848894890489148924893489448954896489748984899490049014902490349044905490649074908490949104911491249134914491549164917491849194920492149224923492449254926492749284929493049314932493349344935493649374938493949404941494249434944494549464947494849494950495149524953495449554956495749584959496049614962496349644965496649674968496949704971497249734974497549764977497849794980498149824983498449854986498749884989499049914992499349944995499649974998499950005001500250035004500550065007500850095010501150125013501450155016501750185019502050215022502350245025502650275028502950305031503250335034503550365037503850395040504150425043504450455046
  1. /* -*- c++ -*- */
  2. /*
  3. Reprap firmware based on Sprinter and grbl.
  4. Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
  5. This program is free software: you can redistribute it and/or modify
  6. it under the terms of the GNU General Public License as published by
  7. the Free Software Foundation, either version 3 of the License, or
  8. (at your option) any later version.
  9. This program is distributed in the hope that it will be useful,
  10. but WITHOUT ANY WARRANTY; without even the implied warranty of
  11. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  12. GNU General Public License for more details.
  13. You should have received a copy of the GNU General Public License
  14. along with this program. If not, see <http://www.gnu.org/licenses/>.
  15. */
  16. /*
  17. This firmware is a mashup between Sprinter and grbl.
  18. (https://github.com/kliment/Sprinter)
  19. (https://github.com/simen/grbl/tree)
  20. It has preliminary support for Matthew Roberts advance algorithm
  21. http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
  22. */
  23. #include "Marlin.h"
  24. #ifdef ENABLE_AUTO_BED_LEVELING
  25. #include "vector_3.h"
  26. #ifdef AUTO_BED_LEVELING_GRID
  27. #include "qr_solve.h"
  28. #endif
  29. #endif // ENABLE_AUTO_BED_LEVELING
  30. #include "ultralcd.h"
  31. #include "Configuration_prusa.h"
  32. #include "planner.h"
  33. #include "stepper.h"
  34. #include "temperature.h"
  35. #include "motion_control.h"
  36. #include "cardreader.h"
  37. #include "watchdog.h"
  38. #include "ConfigurationStore.h"
  39. #include "language.h"
  40. #include "pins_arduino.h"
  41. #include "math.h"
  42. #ifdef BLINKM
  43. #include "BlinkM.h"
  44. #include "Wire.h"
  45. #endif
  46. #ifdef ULTRALCD
  47. #include "ultralcd.h"
  48. #endif
  49. #if NUM_SERVOS > 0
  50. #include "Servo.h"
  51. #endif
  52. #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
  53. #include <SPI.h>
  54. #endif
  55. #define VERSION_STRING "1.0.2"
  56. #include "ultralcd.h"
  57. // look here for descriptions of G-codes: http://linuxcnc.org/handbook/gcode/g-code.html
  58. // http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
  59. //Implemented Codes
  60. //-------------------
  61. // PRUSA CODES
  62. // P F - Returns FW versions
  63. // P R - Returns revision of printer
  64. // G0 -> G1
  65. // G1 - Coordinated Movement X Y Z E
  66. // G2 - CW ARC
  67. // G3 - CCW ARC
  68. // G4 - Dwell S<seconds> or P<milliseconds>
  69. // G10 - retract filament according to settings of M207
  70. // G11 - retract recover filament according to settings of M208
  71. // G28 - Home all Axis
  72. // G29 - Detailed Z-Probe, probes the bed at 3 or more points. Will fail if you haven't homed yet.
  73. // G30 - Single Z Probe, probes bed at current XY location.
  74. // G31 - Dock sled (Z_PROBE_SLED only)
  75. // G32 - Undock sled (Z_PROBE_SLED only)
  76. // G90 - Use Absolute Coordinates
  77. // G91 - Use Relative Coordinates
  78. // G92 - Set current position to coordinates given
  79. // M Codes
  80. // M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled)
  81. // M1 - Same as M0
  82. // M17 - Enable/Power all stepper motors
  83. // M18 - Disable all stepper motors; same as M84
  84. // M20 - List SD card
  85. // M21 - Init SD card
  86. // M22 - Release SD card
  87. // M23 - Select SD file (M23 filename.g)
  88. // M24 - Start/resume SD print
  89. // M25 - Pause SD print
  90. // M26 - Set SD position in bytes (M26 S12345)
  91. // M27 - Report SD print status
  92. // M28 - Start SD write (M28 filename.g)
  93. // M29 - Stop SD write
  94. // M30 - Delete file from SD (M30 filename.g)
  95. // M31 - Output time since last M109 or SD card start to serial
  96. // M32 - Select file and start SD print (Can be used _while_ printing from SD card files):
  97. // syntax "M32 /path/filename#", or "M32 S<startpos bytes> !filename#"
  98. // Call gcode file : "M32 P !filename#" and return to caller file after finishing (similar to #include).
  99. // The '#' is necessary when calling from within sd files, as it stops buffer prereading
  100. // M42 - Change pin status via gcode Use M42 Px Sy to set pin x to value y, when omitting Px the onboard led will be used.
  101. // M80 - Turn on Power Supply
  102. // M81 - Turn off Power Supply
  103. // M82 - Set E codes absolute (default)
  104. // M83 - Set E codes relative while in Absolute Coordinates (G90) mode
  105. // M84 - Disable steppers until next move,
  106. // or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
  107. // M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
  108. // M92 - Set axis_steps_per_unit - same syntax as G92
  109. // M104 - Set extruder target temp
  110. // M105 - Read current temp
  111. // M106 - Fan on
  112. // M107 - Fan off
  113. // M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating
  114. // Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling
  115. // IF AUTOTEMP is enabled, S<mintemp> B<maxtemp> F<factor>. Exit autotemp by any M109 without F
  116. // M112 - Emergency stop
  117. // M114 - Output current position to serial port
  118. // M115 - Capabilities string
  119. // M117 - display message
  120. // M119 - Output Endstop status to serial port
  121. // M126 - Solenoid Air Valve Open (BariCUDA support by jmil)
  122. // M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil)
  123. // M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil)
  124. // M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil)
  125. // M140 - Set bed target temp
  126. // M150 - Set BlinkM Color Output R: Red<0-255> U(!): Green<0-255> B: Blue<0-255> over i2c, G for green does not work.
  127. // M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating
  128. // Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
  129. // M200 D<millimeters>- set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).
  130. // M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
  131. // M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
  132. // M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
  133. // M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) in mm/sec^2 also sets minimum segment time in ms (B20000) to prevent buffer under-runs and M20 minimum feedrate
  134. // M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk, E=maximum E jerk
  135. // M206 - set additional homing offset
  136. // M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop], stays in mm regardless of M200 setting
  137. // M208 - set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/sec]
  138. // M209 - S<1=true/0=false> enable automatic retract detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction.
  139. // M218 - set hotend offset (in mm): T<extruder_number> X<offset_on_X> Y<offset_on_Y>
  140. // M220 S<factor in percent>- set speed factor override percentage
  141. // M221 S<factor in percent>- set extrude factor override percentage
  142. // M226 P<pin number> S<pin state>- Wait until the specified pin reaches the state required
  143. // M240 - Trigger a camera to take a photograph
  144. // M250 - Set LCD contrast C<contrast value> (value 0..63)
  145. // M280 - set servo position absolute. P: servo index, S: angle or microseconds
  146. // M300 - Play beep sound S<frequency Hz> P<duration ms>
  147. // M301 - Set PID parameters P I and D
  148. // M302 - Allow cold extrudes, or set the minimum extrude S<temperature>.
  149. // M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
  150. // M304 - Set bed PID parameters P I and D
  151. // M400 - Finish all moves
  152. // M401 - Lower z-probe if present
  153. // M402 - Raise z-probe if present
  154. // M404 - N<dia in mm> Enter the nominal filament width (3mm, 1.75mm ) or will display nominal filament width without parameters
  155. // M405 - Turn on Filament Sensor extrusion control. Optional D<delay in cm> to set delay in centimeters between sensor and extruder
  156. // M406 - Turn off Filament Sensor extrusion control
  157. // M407 - Displays measured filament diameter
  158. // M500 - stores parameters in EEPROM
  159. // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
  160. // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
  161. // M503 - print the current settings (from memory not from EEPROM)
  162. // M509 - force language selection on next restart
  163. // M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
  164. // M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
  165. // M665 - set delta configurations
  166. // M666 - set delta endstop adjustment
  167. // M605 - Set dual x-carriage movement mode: S<mode> [ X<duplication x-offset> R<duplication temp offset> ]
  168. // M907 - Set digital trimpot motor current using axis codes.
  169. // M908 - Control digital trimpot directly.
  170. // M350 - Set microstepping mode.
  171. // M351 - Toggle MS1 MS2 pins directly.
  172. // ************ SCARA Specific - This can change to suit future G-code regulations
  173. // M360 - SCARA calibration: Move to cal-position ThetaA (0 deg calibration)
  174. // M361 - SCARA calibration: Move to cal-position ThetaB (90 deg calibration - steps per degree)
  175. // M362 - SCARA calibration: Move to cal-position PsiA (0 deg calibration)
  176. // M363 - SCARA calibration: Move to cal-position PsiB (90 deg calibration - steps per degree)
  177. // M364 - SCARA calibration: Move to cal-position PSIC (90 deg to Theta calibration position)
  178. // M365 - SCARA calibration: Scaling factor, X, Y, Z axis
  179. //************* SCARA End ***************
  180. // M928 - Start SD logging (M928 filename.g) - ended by M29
  181. // M999 - Restart after being stopped by error
  182. //Stepper Movement Variables
  183. //===========================================================================
  184. //=============================imported variables============================
  185. //===========================================================================
  186. //===========================================================================
  187. //=============================public variables=============================
  188. //===========================================================================
  189. #ifdef SDSUPPORT
  190. CardReader card;
  191. #endif
  192. union Data
  193. {
  194. byte b[2];
  195. int value;
  196. };
  197. int babystepLoad[3];
  198. float homing_feedrate[] = HOMING_FEEDRATE;
  199. bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
  200. int feedmultiply=100; //100->1 200->2
  201. int saved_feedmultiply;
  202. int extrudemultiply=100; //100->1 200->2
  203. int extruder_multiply[EXTRUDERS] = {100
  204. #if EXTRUDERS > 1
  205. , 100
  206. #if EXTRUDERS > 2
  207. , 100
  208. #endif
  209. #endif
  210. };
  211. int lcd_change_fil_state = 0;
  212. int feedmultiplyBckp = 100;
  213. unsigned char lang_selected = 0;
  214. bool volumetric_enabled = false;
  215. float filament_size[EXTRUDERS] = { DEFAULT_NOMINAL_FILAMENT_DIA
  216. #if EXTRUDERS > 1
  217. , DEFAULT_NOMINAL_FILAMENT_DIA
  218. #if EXTRUDERS > 2
  219. , DEFAULT_NOMINAL_FILAMENT_DIA
  220. #endif
  221. #endif
  222. };
  223. float volumetric_multiplier[EXTRUDERS] = {1.0
  224. #if EXTRUDERS > 1
  225. , 1.0
  226. #if EXTRUDERS > 2
  227. , 1.0
  228. #endif
  229. #endif
  230. };
  231. float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 };
  232. float add_homing[3]={0,0,0};
  233. #ifdef DELTA
  234. float endstop_adj[3]={0,0,0};
  235. #endif
  236. float min_pos[3] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS };
  237. float max_pos[3] = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS };
  238. bool axis_known_position[3] = {false, false, false};
  239. float zprobe_zoffset;
  240. // Extruder offset
  241. #if EXTRUDERS > 1
  242. #ifndef DUAL_X_CARRIAGE
  243. #define NUM_EXTRUDER_OFFSETS 2 // only in XY plane
  244. #else
  245. #define NUM_EXTRUDER_OFFSETS 3 // supports offsets in XYZ plane
  246. #endif
  247. float extruder_offset[NUM_EXTRUDER_OFFSETS][EXTRUDERS] = {
  248. #if defined(EXTRUDER_OFFSET_X) && defined(EXTRUDER_OFFSET_Y)
  249. EXTRUDER_OFFSET_X, EXTRUDER_OFFSET_Y
  250. #endif
  251. };
  252. #endif
  253. uint8_t active_extruder = 0;
  254. int fanSpeed=0;
  255. #ifdef SERVO_ENDSTOPS
  256. int servo_endstops[] = SERVO_ENDSTOPS;
  257. int servo_endstop_angles[] = SERVO_ENDSTOP_ANGLES;
  258. #endif
  259. #ifdef BARICUDA
  260. int ValvePressure=0;
  261. int EtoPPressure=0;
  262. #endif
  263. #ifdef FWRETRACT
  264. bool autoretract_enabled=false;
  265. bool retracted[EXTRUDERS]={false
  266. #if EXTRUDERS > 1
  267. , false
  268. #if EXTRUDERS > 2
  269. , false
  270. #endif
  271. #endif
  272. };
  273. bool retracted_swap[EXTRUDERS]={false
  274. #if EXTRUDERS > 1
  275. , false
  276. #if EXTRUDERS > 2
  277. , false
  278. #endif
  279. #endif
  280. };
  281. float retract_length = RETRACT_LENGTH;
  282. float retract_length_swap = RETRACT_LENGTH_SWAP;
  283. float retract_feedrate = RETRACT_FEEDRATE;
  284. float retract_zlift = RETRACT_ZLIFT;
  285. float retract_recover_length = RETRACT_RECOVER_LENGTH;
  286. float retract_recover_length_swap = RETRACT_RECOVER_LENGTH_SWAP;
  287. float retract_recover_feedrate = RETRACT_RECOVER_FEEDRATE;
  288. #endif
  289. #ifdef ULTIPANEL
  290. #ifdef PS_DEFAULT_OFF
  291. bool powersupply = false;
  292. #else
  293. bool powersupply = true;
  294. #endif
  295. #endif
  296. #ifdef DELTA
  297. float delta[3] = {0.0, 0.0, 0.0};
  298. #define SIN_60 0.8660254037844386
  299. #define COS_60 0.5
  300. // these are the default values, can be overriden with M665
  301. float delta_radius= DELTA_RADIUS;
  302. float delta_tower1_x= -SIN_60*delta_radius; // front left tower
  303. float delta_tower1_y= -COS_60*delta_radius;
  304. float delta_tower2_x= SIN_60*delta_radius; // front right tower
  305. float delta_tower2_y= -COS_60*delta_radius;
  306. float delta_tower3_x= 0.0; // back middle tower
  307. float delta_tower3_y= delta_radius;
  308. float delta_diagonal_rod= DELTA_DIAGONAL_ROD;
  309. float delta_diagonal_rod_2= sq(delta_diagonal_rod);
  310. float delta_segments_per_second= DELTA_SEGMENTS_PER_SECOND;
  311. #endif
  312. #ifdef SCARA // Build size scaling
  313. float axis_scaling[3]={1,1,1}; // Build size scaling, default to 1
  314. #endif
  315. bool cancel_heatup = false ;
  316. #ifdef FILAMENT_SENSOR
  317. //Variables for Filament Sensor input
  318. float filament_width_nominal=DEFAULT_NOMINAL_FILAMENT_DIA; //Set nominal filament width, can be changed with M404
  319. bool filament_sensor=false; //M405 turns on filament_sensor control, M406 turns it off
  320. float filament_width_meas=DEFAULT_MEASURED_FILAMENT_DIA; //Stores the measured filament diameter
  321. signed char measurement_delay[MAX_MEASUREMENT_DELAY+1]; //ring buffer to delay measurement store extruder factor after subtracting 100
  322. int delay_index1=0; //index into ring buffer
  323. int delay_index2=-1; //index into ring buffer - set to -1 on startup to indicate ring buffer needs to be initialized
  324. float delay_dist=0; //delay distance counter
  325. int meas_delay_cm = MEASUREMENT_DELAY_CM; //distance delay setting
  326. #endif
  327. const char errormagic[] PROGMEM = "Error:";
  328. const char echomagic[] PROGMEM = "echo:";
  329. //===========================================================================
  330. //=============================Private Variables=============================
  331. //===========================================================================
  332. const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
  333. static float destination[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0};
  334. #ifndef DELTA
  335. static float delta[3] = {0.0, 0.0, 0.0};
  336. #endif
  337. static float offset[3] = {0.0, 0.0, 0.0};
  338. static bool home_all_axis = true;
  339. static float feedrate = 1500.0, next_feedrate, saved_feedrate;
  340. static long gcode_N, gcode_LastN, Stopped_gcode_LastN = 0;
  341. static bool relative_mode = false; //Determines Absolute or Relative Coordinates
  342. static char cmdbuffer[BUFSIZE][MAX_CMD_SIZE];
  343. static bool fromsd[BUFSIZE];
  344. static int bufindr = 0;
  345. static int bufindw = 0;
  346. static int buflen = 0;
  347. //static int i = 0;
  348. static char serial_char;
  349. static int serial_count = 0;
  350. static boolean comment_mode = false;
  351. static char *strchr_pointer; // just a pointer to find chars in the command string like X, Y, Z, E, etc
  352. const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42
  353. //static float tt = 0;
  354. //static float bt = 0;
  355. //Inactivity shutdown variables
  356. static unsigned long previous_millis_cmd = 0;
  357. static unsigned long max_inactive_time = 0;
  358. static unsigned long stepper_inactive_time = DEFAULT_STEPPER_DEACTIVE_TIME*1000l;
  359. unsigned long starttime=0;
  360. unsigned long stoptime=0;
  361. static uint8_t tmp_extruder;
  362. bool Stopped=false;
  363. #if NUM_SERVOS > 0
  364. Servo servos[NUM_SERVOS];
  365. #endif
  366. bool CooldownNoWait = true;
  367. bool target_direction;
  368. //Insert variables if CHDK is defined
  369. #ifdef CHDK
  370. unsigned long chdkHigh = 0;
  371. boolean chdkActive = false;
  372. #endif
  373. //===========================================================================
  374. //=============================Routines======================================
  375. //===========================================================================
  376. void get_arc_coordinates();
  377. bool setTargetedHotend(int code);
  378. void serial_echopair_P(const char *s_P, float v)
  379. { serialprintPGM(s_P); SERIAL_ECHO(v); }
  380. void serial_echopair_P(const char *s_P, double v)
  381. { serialprintPGM(s_P); SERIAL_ECHO(v); }
  382. void serial_echopair_P(const char *s_P, unsigned long v)
  383. { serialprintPGM(s_P); SERIAL_ECHO(v); }
  384. #ifdef SDSUPPORT
  385. #include "SdFatUtil.h"
  386. int freeMemory() { return SdFatUtil::FreeRam(); }
  387. #else
  388. extern "C" {
  389. extern unsigned int __bss_end;
  390. extern unsigned int __heap_start;
  391. extern void *__brkval;
  392. int freeMemory() {
  393. int free_memory;
  394. if ((int)__brkval == 0)
  395. free_memory = ((int)&free_memory) - ((int)&__bss_end);
  396. else
  397. free_memory = ((int)&free_memory) - ((int)__brkval);
  398. return free_memory;
  399. }
  400. }
  401. #endif //!SDSUPPORT
  402. //adds an command to the main command buffer
  403. //thats really done in a non-safe way.
  404. //needs overworking someday
  405. void enquecommand(const char *cmd)
  406. {
  407. if(buflen < BUFSIZE)
  408. {
  409. //this is dangerous if a mixing of serial and this happens
  410. strcpy(&(cmdbuffer[bufindw][0]),cmd);
  411. SERIAL_ECHO_START;
  412. SERIAL_ECHORPGM(MSG_Enqueing);
  413. SERIAL_ECHO(cmdbuffer[bufindw]);
  414. SERIAL_ECHOLNPGM("\"");
  415. bufindw= (bufindw + 1)%BUFSIZE;
  416. buflen += 1;
  417. }
  418. }
  419. void enquecommand_P(const char *cmd)
  420. {
  421. if(buflen < BUFSIZE)
  422. {
  423. //this is dangerous if a mixing of serial and this happens
  424. strcpy_P(&(cmdbuffer[bufindw][0]),cmd);
  425. SERIAL_ECHO_START;
  426. SERIAL_ECHORPGM(MSG_Enqueing);
  427. SERIAL_ECHO(cmdbuffer[bufindw]);
  428. SERIAL_ECHOLNPGM("\"");
  429. bufindw= (bufindw + 1)%BUFSIZE;
  430. buflen += 1;
  431. }
  432. }
  433. void setup_killpin()
  434. {
  435. #if defined(KILL_PIN) && KILL_PIN > -1
  436. SET_INPUT(KILL_PIN);
  437. WRITE(KILL_PIN,HIGH);
  438. #endif
  439. }
  440. // Set home pin
  441. void setup_homepin(void)
  442. {
  443. #if defined(HOME_PIN) && HOME_PIN > -1
  444. SET_INPUT(HOME_PIN);
  445. WRITE(HOME_PIN,HIGH);
  446. #endif
  447. }
  448. void setup_photpin()
  449. {
  450. #if defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1
  451. SET_OUTPUT(PHOTOGRAPH_PIN);
  452. WRITE(PHOTOGRAPH_PIN, LOW);
  453. #endif
  454. }
  455. void setup_powerhold()
  456. {
  457. #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
  458. SET_OUTPUT(SUICIDE_PIN);
  459. WRITE(SUICIDE_PIN, HIGH);
  460. #endif
  461. #if defined(PS_ON_PIN) && PS_ON_PIN > -1
  462. SET_OUTPUT(PS_ON_PIN);
  463. #if defined(PS_DEFAULT_OFF)
  464. WRITE(PS_ON_PIN, PS_ON_ASLEEP);
  465. #else
  466. WRITE(PS_ON_PIN, PS_ON_AWAKE);
  467. #endif
  468. #endif
  469. }
  470. void suicide()
  471. {
  472. #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
  473. SET_OUTPUT(SUICIDE_PIN);
  474. WRITE(SUICIDE_PIN, LOW);
  475. #endif
  476. }
  477. void servo_init()
  478. {
  479. #if (NUM_SERVOS >= 1) && defined(SERVO0_PIN) && (SERVO0_PIN > -1)
  480. servos[0].attach(SERVO0_PIN);
  481. #endif
  482. #if (NUM_SERVOS >= 2) && defined(SERVO1_PIN) && (SERVO1_PIN > -1)
  483. servos[1].attach(SERVO1_PIN);
  484. #endif
  485. #if (NUM_SERVOS >= 3) && defined(SERVO2_PIN) && (SERVO2_PIN > -1)
  486. servos[2].attach(SERVO2_PIN);
  487. #endif
  488. #if (NUM_SERVOS >= 4) && defined(SERVO3_PIN) && (SERVO3_PIN > -1)
  489. servos[3].attach(SERVO3_PIN);
  490. #endif
  491. #if (NUM_SERVOS >= 5)
  492. #error "TODO: enter initalisation code for more servos"
  493. #endif
  494. // Set position of Servo Endstops that are defined
  495. #ifdef SERVO_ENDSTOPS
  496. for(int8_t i = 0; i < 3; i++)
  497. {
  498. if(servo_endstops[i] > -1) {
  499. servos[servo_endstops[i]].write(servo_endstop_angles[i * 2 + 1]);
  500. }
  501. }
  502. #endif
  503. #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
  504. delay(PROBE_SERVO_DEACTIVATION_DELAY);
  505. servos[servo_endstops[Z_AXIS]].detach();
  506. #endif
  507. }
  508. static void lcd_language_menu();
  509. void setup()
  510. {
  511. setup_killpin();
  512. setup_powerhold();
  513. MYSERIAL.begin(BAUDRATE);
  514. SERIAL_PROTOCOLLNPGM("start");
  515. SERIAL_ECHO_START;
  516. // Check startup - does nothing if bootloader sets MCUSR to 0
  517. byte mcu = MCUSR;
  518. if(mcu & 1) SERIAL_ECHOLNRPGM(MSG_POWERUP);
  519. if(mcu & 2) SERIAL_ECHOLNRPGM(MSG_EXTERNAL_RESET);
  520. if(mcu & 4) SERIAL_ECHOLNRPGM(MSG_BROWNOUT_RESET);
  521. if(mcu & 8) SERIAL_ECHOLNRPGM(MSG_WATCHDOG_RESET);
  522. if(mcu & 32) SERIAL_ECHOLNRPGM(MSG_SOFTWARE_RESET);
  523. MCUSR=0;
  524. SERIAL_ECHORPGM(MSG_MARLIN);
  525. SERIAL_ECHOLNRPGM(VERSION_STRING);
  526. #ifdef STRING_VERSION_CONFIG_H
  527. #ifdef STRING_CONFIG_H_AUTHOR
  528. SERIAL_ECHO_START;
  529. SERIAL_ECHORPGM(MSG_CONFIGURATION_VER);
  530. SERIAL_ECHOPGM(STRING_VERSION_CONFIG_H);
  531. SERIAL_ECHORPGM(MSG_AUTHOR);
  532. SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR);
  533. SERIAL_ECHOPGM("Compiled: ");
  534. SERIAL_ECHOLNPGM(__DATE__);
  535. #endif
  536. #endif
  537. SERIAL_ECHO_START;
  538. SERIAL_ECHORPGM(MSG_FREE_MEMORY);
  539. SERIAL_ECHO(freeMemory());
  540. SERIAL_ECHORPGM(MSG_PLANNER_BUFFER_BYTES);
  541. SERIAL_ECHOLN((int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
  542. for(int8_t i = 0; i < BUFSIZE; i++)
  543. {
  544. fromsd[i] = false;
  545. }
  546. // loads data from EEPROM if available else uses defaults (and resets step acceleration rate)
  547. Config_RetrieveSettings();
  548. tp_init(); // Initialize temperature loop
  549. plan_init(); // Initialize planner;
  550. watchdog_init();
  551. st_init(); // Initialize stepper, this enables interrupts!
  552. setup_photpin();
  553. servo_init();
  554. lcd_init();
  555. if(!READ(BTN_ENC) ){
  556. _delay_ms(1000);
  557. if(!READ(BTN_ENC) ){
  558. SET_OUTPUT(BEEPER);
  559. WRITE(BEEPER,HIGH);
  560. lcd_force_language_selection();
  561. while(!READ(BTN_ENC));
  562. WRITE(BEEPER,LOW);
  563. }
  564. }else{
  565. _delay_ms(1000); // wait 1sec to display the splash screen
  566. }
  567. #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
  568. SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
  569. #endif
  570. #ifdef DIGIPOT_I2C
  571. digipot_i2c_init();
  572. #endif
  573. #ifdef Z_PROBE_SLED
  574. pinMode(SERVO0_PIN, OUTPUT);
  575. digitalWrite(SERVO0_PIN, LOW); // turn it off
  576. #endif // Z_PROBE_SLED
  577. setup_homepin();
  578. }
  579. //unsigned char first_run_ever=1;
  580. //void first_time_menu();
  581. void loop()
  582. {
  583. if(buflen < (BUFSIZE-1))
  584. get_command();
  585. #ifdef SDSUPPORT
  586. card.checkautostart(false);
  587. #endif
  588. if(buflen)
  589. {
  590. #ifdef SDSUPPORT
  591. if(card.saving)
  592. {
  593. if(strstr_P(cmdbuffer[bufindr], PSTR("M29")) == NULL)
  594. {
  595. card.write_command(cmdbuffer[bufindr]);
  596. if(card.logging)
  597. {
  598. process_commands();
  599. }
  600. else
  601. {
  602. SERIAL_PROTOCOLLNRPGM(MSG_OK);
  603. }
  604. }
  605. else
  606. {
  607. card.closefile();
  608. SERIAL_PROTOCOLLNRPGM(MSG_FILE_SAVED);
  609. }
  610. }
  611. else
  612. {
  613. process_commands();
  614. }
  615. #else
  616. process_commands();
  617. #endif //SDSUPPORT
  618. buflen = (buflen-1);
  619. bufindr = (bufindr + 1)%BUFSIZE;
  620. }
  621. //check heater every n milliseconds
  622. manage_heater();
  623. manage_inactivity();
  624. checkHitEndstops();
  625. lcd_update();
  626. }
  627. void get_command()
  628. {
  629. while( MYSERIAL.available() > 0 && buflen < BUFSIZE) {
  630. serial_char = MYSERIAL.read();
  631. if(serial_char == '\n' ||
  632. serial_char == '\r' ||
  633. (serial_char == ':' && comment_mode == false) ||
  634. serial_count >= (MAX_CMD_SIZE - 1) )
  635. {
  636. if(!serial_count) { //if empty line
  637. comment_mode = false; //for new command
  638. return;
  639. }
  640. cmdbuffer[bufindw][serial_count] = 0; //terminate string
  641. if(!comment_mode){
  642. comment_mode = false; //for new command
  643. fromsd[bufindw] = false;
  644. if(strchr(cmdbuffer[bufindw], 'N') != NULL)
  645. {
  646. strchr_pointer = strchr(cmdbuffer[bufindw], 'N');
  647. gcode_N = (strtol(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL, 10));
  648. if(gcode_N != gcode_LastN+1 && (strstr_P(cmdbuffer[bufindw], PSTR("M110")) == NULL) ) {
  649. SERIAL_ERROR_START;
  650. SERIAL_ERRORRPGM(MSG_ERR_LINE_NO);
  651. SERIAL_ERRORLN(gcode_LastN);
  652. //Serial.println(gcode_N);
  653. FlushSerialRequestResend();
  654. serial_count = 0;
  655. return;
  656. }
  657. if(strchr(cmdbuffer[bufindw], '*') != NULL)
  658. {
  659. byte checksum = 0;
  660. byte count = 0;
  661. while(cmdbuffer[bufindw][count] != '*') checksum = checksum^cmdbuffer[bufindw][count++];
  662. strchr_pointer = strchr(cmdbuffer[bufindw], '*');
  663. if( (int)(strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)) != checksum) {
  664. SERIAL_ERROR_START;
  665. SERIAL_ERRORRPGM(MSG_ERR_CHECKSUM_MISMATCH);
  666. SERIAL_ERRORLN(gcode_LastN);
  667. FlushSerialRequestResend();
  668. serial_count = 0;
  669. return;
  670. }
  671. //if no errors, continue parsing
  672. }
  673. else
  674. {
  675. SERIAL_ERROR_START;
  676. SERIAL_ERRORRPGM(MSG_ERR_NO_CHECKSUM);
  677. SERIAL_ERRORLN(gcode_LastN);
  678. FlushSerialRequestResend();
  679. serial_count = 0;
  680. return;
  681. }
  682. gcode_LastN = gcode_N;
  683. //if no errors, continue parsing
  684. }
  685. else // if we don't receive 'N' but still see '*'
  686. {
  687. if((strchr(cmdbuffer[bufindw], '*') != NULL))
  688. {
  689. SERIAL_ERROR_START;
  690. SERIAL_ERRORRPGM(MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM);
  691. SERIAL_ERRORLN(gcode_LastN);
  692. serial_count = 0;
  693. return;
  694. }
  695. }
  696. if((strchr(cmdbuffer[bufindw], 'G') != NULL)){
  697. strchr_pointer = strchr(cmdbuffer[bufindw], 'G');
  698. switch((int)((strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)))){
  699. case 0:
  700. case 1:
  701. case 2:
  702. case 3:
  703. if (Stopped == true) {
  704. SERIAL_ERRORLNRPGM(MSG_ERR_STOPPED);
  705. LCD_MESSAGERPGM(MSG_STOPPED);
  706. }
  707. break;
  708. default:
  709. break;
  710. }
  711. }
  712. //If command was e-stop process now
  713. if(strcmp(cmdbuffer[bufindw], "M112") == 0)
  714. kill();
  715. bufindw = (bufindw + 1)%BUFSIZE;
  716. buflen += 1;
  717. }
  718. serial_count = 0; //clear buffer
  719. }
  720. else
  721. {
  722. if(serial_char == ';') comment_mode = true;
  723. if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char;
  724. }
  725. }
  726. #ifdef SDSUPPORT
  727. if(!card.sdprinting || serial_count!=0){
  728. return;
  729. }
  730. //'#' stops reading from SD to the buffer prematurely, so procedural macro calls are possible
  731. // if it occurs, stop_buffering is triggered and the buffer is ran dry.
  732. // this character _can_ occur in serial com, due to checksums. however, no checksums are used in SD printing
  733. static bool stop_buffering=false;
  734. if(buflen==0) stop_buffering=false;
  735. while( !card.eof() && buflen < BUFSIZE && !stop_buffering) {
  736. int16_t n=card.get();
  737. serial_char = (char)n;
  738. if(serial_char == '\n' ||
  739. serial_char == '\r' ||
  740. (serial_char == '#' && comment_mode == false) ||
  741. (serial_char == ':' && comment_mode == false) ||
  742. serial_count >= (MAX_CMD_SIZE - 1)||n==-1)
  743. {
  744. if(card.eof()){
  745. SERIAL_PROTOCOLLNRPGM(MSG_FILE_PRINTED);
  746. stoptime=millis();
  747. char time[30];
  748. unsigned long t=(stoptime-starttime)/1000;
  749. int hours, minutes;
  750. minutes=(t/60)%60;
  751. hours=t/60/60;
  752. sprintf_P(time, PSTR("%i hours %i minutes"),hours, minutes);
  753. SERIAL_ECHO_START;
  754. SERIAL_ECHOLN(time);
  755. lcd_setstatus(time);
  756. card.printingHasFinished();
  757. card.checkautostart(true);
  758. }
  759. if(serial_char=='#')
  760. stop_buffering=true;
  761. if(!serial_count)
  762. {
  763. comment_mode = false; //for new command
  764. return; //if empty line
  765. }
  766. cmdbuffer[bufindw][serial_count] = 0; //terminate string
  767. // if(!comment_mode){
  768. fromsd[bufindw] = true;
  769. buflen += 1;
  770. bufindw = (bufindw + 1)%BUFSIZE;
  771. // }
  772. comment_mode = false; //for new command
  773. serial_count = 0; //clear buffer
  774. }
  775. else
  776. {
  777. if(serial_char == ';') comment_mode = true;
  778. if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char;
  779. }
  780. }
  781. #endif //SDSUPPORT
  782. }
  783. float code_value()
  784. {
  785. return (strtod(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL));
  786. }
  787. long code_value_long()
  788. {
  789. return (strtol(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL, 10));
  790. }
  791. bool code_seen(char code)
  792. {
  793. strchr_pointer = strchr(cmdbuffer[bufindr], code);
  794. return (strchr_pointer != NULL); //Return True if a character was found
  795. }
  796. #define DEFINE_PGM_READ_ANY(type, reader) \
  797. static inline type pgm_read_any(const type *p) \
  798. { return pgm_read_##reader##_near(p); }
  799. DEFINE_PGM_READ_ANY(float, float);
  800. DEFINE_PGM_READ_ANY(signed char, byte);
  801. #define XYZ_CONSTS_FROM_CONFIG(type, array, CONFIG) \
  802. static const PROGMEM type array##_P[3] = \
  803. { X_##CONFIG, Y_##CONFIG, Z_##CONFIG }; \
  804. static inline type array(int axis) \
  805. { return pgm_read_any(&array##_P[axis]); }
  806. XYZ_CONSTS_FROM_CONFIG(float, base_min_pos, MIN_POS);
  807. XYZ_CONSTS_FROM_CONFIG(float, base_max_pos, MAX_POS);
  808. XYZ_CONSTS_FROM_CONFIG(float, base_home_pos, HOME_POS);
  809. XYZ_CONSTS_FROM_CONFIG(float, max_length, MAX_LENGTH);
  810. XYZ_CONSTS_FROM_CONFIG(float, home_retract_mm, HOME_RETRACT_MM);
  811. XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR);
  812. #ifdef DUAL_X_CARRIAGE
  813. #if EXTRUDERS == 1 || defined(COREXY) \
  814. || !defined(X2_ENABLE_PIN) || !defined(X2_STEP_PIN) || !defined(X2_DIR_PIN) \
  815. || !defined(X2_HOME_POS) || !defined(X2_MIN_POS) || !defined(X2_MAX_POS) \
  816. || !defined(X_MAX_PIN) || X_MAX_PIN < 0
  817. #error "Missing or invalid definitions for DUAL_X_CARRIAGE mode."
  818. #endif
  819. #if X_HOME_DIR != -1 || X2_HOME_DIR != 1
  820. #error "Please use canonical x-carriage assignment" // the x-carriages are defined by their homing directions
  821. #endif
  822. #define DXC_FULL_CONTROL_MODE 0
  823. #define DXC_AUTO_PARK_MODE 1
  824. #define DXC_DUPLICATION_MODE 2
  825. static int dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
  826. static float x_home_pos(int extruder) {
  827. if (extruder == 0)
  828. return base_home_pos(X_AXIS) + add_homing[X_AXIS];
  829. else
  830. // In dual carriage mode the extruder offset provides an override of the
  831. // second X-carriage offset when homed - otherwise X2_HOME_POS is used.
  832. // This allow soft recalibration of the second extruder offset position without firmware reflash
  833. // (through the M218 command).
  834. return (extruder_offset[X_AXIS][1] > 0) ? extruder_offset[X_AXIS][1] : X2_HOME_POS;
  835. }
  836. static int x_home_dir(int extruder) {
  837. return (extruder == 0) ? X_HOME_DIR : X2_HOME_DIR;
  838. }
  839. static float inactive_extruder_x_pos = X2_MAX_POS; // used in mode 0 & 1
  840. static bool active_extruder_parked = false; // used in mode 1 & 2
  841. static float raised_parked_position[NUM_AXIS]; // used in mode 1
  842. static unsigned long delayed_move_time = 0; // used in mode 1
  843. static float duplicate_extruder_x_offset = DEFAULT_DUPLICATION_X_OFFSET; // used in mode 2
  844. static float duplicate_extruder_temp_offset = 0; // used in mode 2
  845. bool extruder_duplication_enabled = false; // used in mode 2
  846. #endif //DUAL_X_CARRIAGE
  847. static void axis_is_at_home(int axis) {
  848. #ifdef DUAL_X_CARRIAGE
  849. if (axis == X_AXIS) {
  850. if (active_extruder != 0) {
  851. current_position[X_AXIS] = x_home_pos(active_extruder);
  852. min_pos[X_AXIS] = X2_MIN_POS;
  853. max_pos[X_AXIS] = max(extruder_offset[X_AXIS][1], X2_MAX_POS);
  854. return;
  855. }
  856. else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && active_extruder == 0) {
  857. current_position[X_AXIS] = base_home_pos(X_AXIS) + add_homing[X_AXIS];
  858. min_pos[X_AXIS] = base_min_pos(X_AXIS) + add_homing[X_AXIS];
  859. max_pos[X_AXIS] = min(base_max_pos(X_AXIS) + add_homing[X_AXIS],
  860. max(extruder_offset[X_AXIS][1], X2_MAX_POS) - duplicate_extruder_x_offset);
  861. return;
  862. }
  863. }
  864. #endif
  865. #ifdef SCARA
  866. float homeposition[3];
  867. char i;
  868. if (axis < 2)
  869. {
  870. for (i=0; i<3; i++)
  871. {
  872. homeposition[i] = base_home_pos(i);
  873. }
  874. // SERIAL_ECHOPGM("homeposition[x]= "); SERIAL_ECHO(homeposition[0]);
  875. // SERIAL_ECHOPGM("homeposition[y]= "); SERIAL_ECHOLN(homeposition[1]);
  876. // Works out real Homeposition angles using inverse kinematics,
  877. // and calculates homing offset using forward kinematics
  878. calculate_delta(homeposition);
  879. // SERIAL_ECHOPGM("base Theta= "); SERIAL_ECHO(delta[X_AXIS]);
  880. // SERIAL_ECHOPGM(" base Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
  881. for (i=0; i<2; i++)
  882. {
  883. delta[i] -= add_homing[i];
  884. }
  885. // SERIAL_ECHOPGM("addhome X="); SERIAL_ECHO(add_homing[X_AXIS]);
  886. // SERIAL_ECHOPGM(" addhome Y="); SERIAL_ECHO(add_homing[Y_AXIS]);
  887. // SERIAL_ECHOPGM(" addhome Theta="); SERIAL_ECHO(delta[X_AXIS]);
  888. // SERIAL_ECHOPGM(" addhome Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
  889. calculate_SCARA_forward_Transform(delta);
  890. // SERIAL_ECHOPGM("Delta X="); SERIAL_ECHO(delta[X_AXIS]);
  891. // SERIAL_ECHOPGM(" Delta Y="); SERIAL_ECHOLN(delta[Y_AXIS]);
  892. current_position[axis] = delta[axis];
  893. // SCARA home positions are based on configuration since the actual limits are determined by the
  894. // inverse kinematic transform.
  895. min_pos[axis] = base_min_pos(axis); // + (delta[axis] - base_home_pos(axis));
  896. max_pos[axis] = base_max_pos(axis); // + (delta[axis] - base_home_pos(axis));
  897. }
  898. else
  899. {
  900. current_position[axis] = base_home_pos(axis) + add_homing[axis];
  901. min_pos[axis] = base_min_pos(axis) + add_homing[axis];
  902. max_pos[axis] = base_max_pos(axis) + add_homing[axis];
  903. }
  904. #else
  905. current_position[axis] = base_home_pos(axis) + add_homing[axis];
  906. min_pos[axis] = base_min_pos(axis) + add_homing[axis];
  907. max_pos[axis] = base_max_pos(axis) + add_homing[axis];
  908. #endif
  909. }
  910. #ifdef ENABLE_AUTO_BED_LEVELING
  911. #ifdef AUTO_BED_LEVELING_GRID
  912. static void set_bed_level_equation_lsq(double *plane_equation_coefficients)
  913. {
  914. vector_3 planeNormal = vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1);
  915. planeNormal.debug("planeNormal");
  916. plan_bed_level_matrix = matrix_3x3::create_look_at(planeNormal);
  917. //bedLevel.debug("bedLevel");
  918. //plan_bed_level_matrix.debug("bed level before");
  919. //vector_3 uncorrected_position = plan_get_position_mm();
  920. //uncorrected_position.debug("position before");
  921. vector_3 corrected_position = plan_get_position();
  922. // corrected_position.debug("position after");
  923. current_position[X_AXIS] = corrected_position.x;
  924. current_position[Y_AXIS] = corrected_position.y;
  925. current_position[Z_AXIS] = corrected_position.z;
  926. // put the bed at 0 so we don't go below it.
  927. current_position[Z_AXIS] = zprobe_zoffset; // in the lsq we reach here after raising the extruder due to the loop structure
  928. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  929. }
  930. #else // not AUTO_BED_LEVELING_GRID
  931. static void set_bed_level_equation_3pts(float z_at_pt_1, float z_at_pt_2, float z_at_pt_3) {
  932. plan_bed_level_matrix.set_to_identity();
  933. vector_3 pt1 = vector_3(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, z_at_pt_1);
  934. vector_3 pt2 = vector_3(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, z_at_pt_2);
  935. vector_3 pt3 = vector_3(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, z_at_pt_3);
  936. vector_3 from_2_to_1 = (pt1 - pt2).get_normal();
  937. vector_3 from_2_to_3 = (pt3 - pt2).get_normal();
  938. vector_3 planeNormal = vector_3::cross(from_2_to_1, from_2_to_3).get_normal();
  939. planeNormal = vector_3(planeNormal.x, planeNormal.y, abs(planeNormal.z));
  940. plan_bed_level_matrix = matrix_3x3::create_look_at(planeNormal);
  941. vector_3 corrected_position = plan_get_position();
  942. current_position[X_AXIS] = corrected_position.x;
  943. current_position[Y_AXIS] = corrected_position.y;
  944. current_position[Z_AXIS] = corrected_position.z;
  945. // put the bed at 0 so we don't go below it.
  946. current_position[Z_AXIS] = zprobe_zoffset;
  947. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  948. }
  949. #endif // AUTO_BED_LEVELING_GRID
  950. static void run_z_probe() {
  951. plan_bed_level_matrix.set_to_identity();
  952. feedrate = homing_feedrate[Z_AXIS];
  953. // move down until you find the bed
  954. float zPosition = -10;
  955. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate/60, active_extruder);
  956. st_synchronize();
  957. // we have to let the planner know where we are right now as it is not where we said to go.
  958. zPosition = st_get_position_mm(Z_AXIS);
  959. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS]);
  960. // move up the retract distance
  961. zPosition += home_retract_mm(Z_AXIS);
  962. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate/60, active_extruder);
  963. st_synchronize();
  964. // move back down slowly to find bed
  965. feedrate = homing_feedrate[Z_AXIS]/4;
  966. zPosition -= home_retract_mm(Z_AXIS) * 2;
  967. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate/60, active_extruder);
  968. st_synchronize();
  969. current_position[Z_AXIS] = st_get_position_mm(Z_AXIS);
  970. // make sure the planner knows where we are as it may be a bit different than we last said to move to
  971. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  972. }
  973. static void do_blocking_move_to(float x, float y, float z) {
  974. float oldFeedRate = feedrate;
  975. feedrate = homing_feedrate[Z_AXIS];
  976. current_position[Z_AXIS] = z;
  977. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate/60, active_extruder);
  978. st_synchronize();
  979. feedrate = XY_TRAVEL_SPEED;
  980. current_position[X_AXIS] = x;
  981. current_position[Y_AXIS] = y;
  982. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate/60, active_extruder);
  983. st_synchronize();
  984. feedrate = oldFeedRate;
  985. }
  986. static void do_blocking_move_relative(float offset_x, float offset_y, float offset_z) {
  987. do_blocking_move_to(current_position[X_AXIS] + offset_x, current_position[Y_AXIS] + offset_y, current_position[Z_AXIS] + offset_z);
  988. }
  989. static void setup_for_endstop_move() {
  990. saved_feedrate = feedrate;
  991. saved_feedmultiply = feedmultiply;
  992. feedmultiply = 100;
  993. previous_millis_cmd = millis();
  994. enable_endstops(true);
  995. }
  996. static void clean_up_after_endstop_move() {
  997. #ifdef ENDSTOPS_ONLY_FOR_HOMING
  998. enable_endstops(false);
  999. #endif
  1000. feedrate = saved_feedrate;
  1001. feedmultiply = saved_feedmultiply;
  1002. previous_millis_cmd = millis();
  1003. }
  1004. static void engage_z_probe() {
  1005. // Engage Z Servo endstop if enabled
  1006. #ifdef SERVO_ENDSTOPS
  1007. if (servo_endstops[Z_AXIS] > -1) {
  1008. #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
  1009. servos[servo_endstops[Z_AXIS]].attach(0);
  1010. #endif
  1011. servos[servo_endstops[Z_AXIS]].write(servo_endstop_angles[Z_AXIS * 2]);
  1012. #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
  1013. delay(PROBE_SERVO_DEACTIVATION_DELAY);
  1014. servos[servo_endstops[Z_AXIS]].detach();
  1015. #endif
  1016. }
  1017. #endif
  1018. }
  1019. static void retract_z_probe() {
  1020. // Retract Z Servo endstop if enabled
  1021. #ifdef SERVO_ENDSTOPS
  1022. if (servo_endstops[Z_AXIS] > -1) {
  1023. #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
  1024. servos[servo_endstops[Z_AXIS]].attach(0);
  1025. #endif
  1026. servos[servo_endstops[Z_AXIS]].write(servo_endstop_angles[Z_AXIS * 2 + 1]);
  1027. #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
  1028. delay(PROBE_SERVO_DEACTIVATION_DELAY);
  1029. servos[servo_endstops[Z_AXIS]].detach();
  1030. #endif
  1031. }
  1032. #endif
  1033. }
  1034. /// Probe bed height at position (x,y), returns the measured z value
  1035. static float probe_pt(float x, float y, float z_before) {
  1036. // move to right place
  1037. do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z_before);
  1038. do_blocking_move_to(x - X_PROBE_OFFSET_FROM_EXTRUDER, y - Y_PROBE_OFFSET_FROM_EXTRUDER, current_position[Z_AXIS]);
  1039. #ifndef Z_PROBE_SLED
  1040. engage_z_probe(); // Engage Z Servo endstop if available
  1041. #endif // Z_PROBE_SLED
  1042. run_z_probe();
  1043. float measured_z = current_position[Z_AXIS];
  1044. #ifndef Z_PROBE_SLED
  1045. retract_z_probe();
  1046. #endif // Z_PROBE_SLED
  1047. SERIAL_PROTOCOLRPGM(MSG_BED);
  1048. SERIAL_PROTOCOLPGM(" x: ");
  1049. SERIAL_PROTOCOL(x);
  1050. SERIAL_PROTOCOLPGM(" y: ");
  1051. SERIAL_PROTOCOL(y);
  1052. SERIAL_PROTOCOLPGM(" z: ");
  1053. SERIAL_PROTOCOL(measured_z);
  1054. SERIAL_PROTOCOLPGM("\n");
  1055. return measured_z;
  1056. }
  1057. #endif // #ifdef ENABLE_AUTO_BED_LEVELING
  1058. static void homeaxis(int axis) {
  1059. #define HOMEAXIS_DO(LETTER) \
  1060. ((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1))
  1061. if (axis==X_AXIS ? HOMEAXIS_DO(X) :
  1062. axis==Y_AXIS ? HOMEAXIS_DO(Y) :
  1063. axis==Z_AXIS ? HOMEAXIS_DO(Z) :
  1064. 0) {
  1065. int axis_home_dir = home_dir(axis);
  1066. #ifdef DUAL_X_CARRIAGE
  1067. if (axis == X_AXIS)
  1068. axis_home_dir = x_home_dir(active_extruder);
  1069. #endif
  1070. current_position[axis] = 0;
  1071. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1072. #ifndef Z_PROBE_SLED
  1073. // Engage Servo endstop if enabled
  1074. #ifdef SERVO_ENDSTOPS
  1075. #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
  1076. if (axis==Z_AXIS) {
  1077. engage_z_probe();
  1078. }
  1079. else
  1080. #endif
  1081. if (servo_endstops[axis] > -1) {
  1082. servos[servo_endstops[axis]].write(servo_endstop_angles[axis * 2]);
  1083. }
  1084. #endif
  1085. #endif // Z_PROBE_SLED
  1086. destination[axis] = 1.5 * max_length(axis) * axis_home_dir;
  1087. feedrate = homing_feedrate[axis];
  1088. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1089. st_synchronize();
  1090. current_position[axis] = 0;
  1091. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1092. destination[axis] = -home_retract_mm(axis) * axis_home_dir;
  1093. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1094. st_synchronize();
  1095. destination[axis] = 2*home_retract_mm(axis) * axis_home_dir;
  1096. #ifdef DELTA
  1097. feedrate = homing_feedrate[axis]/10;
  1098. #else
  1099. feedrate = homing_feedrate[axis]/2 ;
  1100. #endif
  1101. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1102. st_synchronize();
  1103. #ifdef DELTA
  1104. // retrace by the amount specified in endstop_adj
  1105. if (endstop_adj[axis] * axis_home_dir < 0) {
  1106. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1107. destination[axis] = endstop_adj[axis];
  1108. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1109. st_synchronize();
  1110. }
  1111. #endif
  1112. axis_is_at_home(axis);
  1113. destination[axis] = current_position[axis];
  1114. feedrate = 0.0;
  1115. endstops_hit_on_purpose();
  1116. axis_known_position[axis] = true;
  1117. // Retract Servo endstop if enabled
  1118. #ifdef SERVO_ENDSTOPS
  1119. if (servo_endstops[axis] > -1) {
  1120. servos[servo_endstops[axis]].write(servo_endstop_angles[axis * 2 + 1]);
  1121. }
  1122. #endif
  1123. #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
  1124. #ifndef Z_PROBE_SLED
  1125. if (axis==Z_AXIS) retract_z_probe();
  1126. #endif
  1127. #endif
  1128. }
  1129. }
  1130. #define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS)
  1131. void refresh_cmd_timeout(void)
  1132. {
  1133. previous_millis_cmd = millis();
  1134. }
  1135. #ifdef FWRETRACT
  1136. void retract(bool retracting, bool swapretract = false) {
  1137. if(retracting && !retracted[active_extruder]) {
  1138. destination[X_AXIS]=current_position[X_AXIS];
  1139. destination[Y_AXIS]=current_position[Y_AXIS];
  1140. destination[Z_AXIS]=current_position[Z_AXIS];
  1141. destination[E_AXIS]=current_position[E_AXIS];
  1142. if (swapretract) {
  1143. current_position[E_AXIS]+=retract_length_swap/volumetric_multiplier[active_extruder];
  1144. } else {
  1145. current_position[E_AXIS]+=retract_length/volumetric_multiplier[active_extruder];
  1146. }
  1147. plan_set_e_position(current_position[E_AXIS]);
  1148. float oldFeedrate = feedrate;
  1149. feedrate=retract_feedrate*60;
  1150. retracted[active_extruder]=true;
  1151. prepare_move();
  1152. current_position[Z_AXIS]-=retract_zlift;
  1153. #ifdef DELTA
  1154. calculate_delta(current_position); // change cartesian kinematic to delta kinematic;
  1155. plan_set_position(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS]);
  1156. #else
  1157. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1158. #endif
  1159. prepare_move();
  1160. feedrate = oldFeedrate;
  1161. } else if(!retracting && retracted[active_extruder]) {
  1162. destination[X_AXIS]=current_position[X_AXIS];
  1163. destination[Y_AXIS]=current_position[Y_AXIS];
  1164. destination[Z_AXIS]=current_position[Z_AXIS];
  1165. destination[E_AXIS]=current_position[E_AXIS];
  1166. current_position[Z_AXIS]+=retract_zlift;
  1167. #ifdef DELTA
  1168. calculate_delta(current_position); // change cartesian kinematic to delta kinematic;
  1169. plan_set_position(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS]);
  1170. #else
  1171. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1172. #endif
  1173. //prepare_move();
  1174. if (swapretract) {
  1175. current_position[E_AXIS]-=(retract_length_swap+retract_recover_length_swap)/volumetric_multiplier[active_extruder];
  1176. } else {
  1177. current_position[E_AXIS]-=(retract_length+retract_recover_length)/volumetric_multiplier[active_extruder];
  1178. }
  1179. plan_set_e_position(current_position[E_AXIS]);
  1180. float oldFeedrate = feedrate;
  1181. feedrate=retract_recover_feedrate*60;
  1182. retracted[active_extruder]=false;
  1183. prepare_move();
  1184. feedrate = oldFeedrate;
  1185. }
  1186. } //retract
  1187. #endif //FWRETRACT
  1188. #ifdef Z_PROBE_SLED
  1189. //
  1190. // Method to dock/undock a sled designed by Charles Bell.
  1191. //
  1192. // dock[in] If true, move to MAX_X and engage the electromagnet
  1193. // offset[in] The additional distance to move to adjust docking location
  1194. //
  1195. static void dock_sled(bool dock, int offset=0) {
  1196. int z_loc;
  1197. if (!((axis_known_position[X_AXIS]) && (axis_known_position[Y_AXIS]))) {
  1198. LCD_MESSAGERPGM(MSG_POSITION_UNKNOWN);
  1199. SERIAL_ECHO_START;
  1200. SERIAL_ECHOLNRPGM(MSG_POSITION_UNKNOWN);
  1201. return;
  1202. }
  1203. if (dock) {
  1204. do_blocking_move_to(X_MAX_POS + SLED_DOCKING_OFFSET + offset,
  1205. current_position[Y_AXIS],
  1206. current_position[Z_AXIS]);
  1207. // turn off magnet
  1208. digitalWrite(SERVO0_PIN, LOW);
  1209. } else {
  1210. if (current_position[Z_AXIS] < (Z_RAISE_BEFORE_PROBING + 5))
  1211. z_loc = Z_RAISE_BEFORE_PROBING;
  1212. else
  1213. z_loc = current_position[Z_AXIS];
  1214. do_blocking_move_to(X_MAX_POS + SLED_DOCKING_OFFSET + offset,
  1215. Y_PROBE_OFFSET_FROM_EXTRUDER, z_loc);
  1216. // turn on magnet
  1217. digitalWrite(SERVO0_PIN, HIGH);
  1218. }
  1219. }
  1220. #endif
  1221. void process_commands()
  1222. {
  1223. #ifdef FILAMENT_RUNOUT_SUPPORT
  1224. SET_INPUT(FR_SENS);
  1225. #endif
  1226. unsigned long codenum; //throw away variable
  1227. char *starpos = NULL;
  1228. #ifdef ENABLE_AUTO_BED_LEVELING
  1229. float x_tmp, y_tmp, z_tmp, real_z;
  1230. #endif
  1231. // PRUSA GCODES
  1232. if(code_seen('PRUSA')){
  1233. if(code_seen('Fir')){
  1234. SERIAL_PROTOCOLLN(FW_version);
  1235. } else if(code_seen('Rev')){
  1236. SERIAL_PROTOCOLLN(FILAMENT_SIZE "-" ELECTRONICS "-" NOZZLE_TYPE );
  1237. } else if(code_seen('Lang')) {
  1238. lcd_force_language_selection();
  1239. } else if(code_seen('Lz')) {
  1240. EEPROM_save_B(EEPROM_BABYSTEP_Z,0);
  1241. }
  1242. }
  1243. else if(code_seen('G'))
  1244. {
  1245. switch((int)code_value())
  1246. {
  1247. case 0: // G0 -> G1
  1248. case 1: // G1
  1249. if(Stopped == false) {
  1250. #ifdef FILAMENT_RUNOUT_SUPPORT
  1251. if(READ(FR_SENS)){
  1252. feedmultiplyBckp=feedmultiply;
  1253. float target[4];
  1254. float lastpos[4];
  1255. target[X_AXIS]=current_position[X_AXIS];
  1256. target[Y_AXIS]=current_position[Y_AXIS];
  1257. target[Z_AXIS]=current_position[Z_AXIS];
  1258. target[E_AXIS]=current_position[E_AXIS];
  1259. lastpos[X_AXIS]=current_position[X_AXIS];
  1260. lastpos[Y_AXIS]=current_position[Y_AXIS];
  1261. lastpos[Z_AXIS]=current_position[Z_AXIS];
  1262. lastpos[E_AXIS]=current_position[E_AXIS];
  1263. //retract by E
  1264. target[E_AXIS]+= FILAMENTCHANGE_FIRSTRETRACT ;
  1265. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 400, active_extruder);
  1266. target[Z_AXIS]+= FILAMENTCHANGE_ZADD ;
  1267. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 300, active_extruder);
  1268. target[X_AXIS]= FILAMENTCHANGE_XPOS ;
  1269. target[Y_AXIS]= FILAMENTCHANGE_YPOS ;
  1270. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 70, active_extruder);
  1271. target[E_AXIS]+= FILAMENTCHANGE_FINALRETRACT ;
  1272. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 20, active_extruder);
  1273. //finish moves
  1274. st_synchronize();
  1275. //disable extruder steppers so filament can be removed
  1276. disable_e0();
  1277. disable_e1();
  1278. disable_e2();
  1279. delay(100);
  1280. //LCD_ALERTMESSAGEPGM(MSG_FILAMENTCHANGE);
  1281. uint8_t cnt=0;
  1282. int counterBeep = 0;
  1283. lcd_wait_interact();
  1284. while(!lcd_clicked()){
  1285. cnt++;
  1286. manage_heater();
  1287. manage_inactivity(true);
  1288. //lcd_update();
  1289. if(cnt==0)
  1290. {
  1291. #if BEEPER > 0
  1292. if (counterBeep== 500){
  1293. counterBeep = 0;
  1294. }
  1295. SET_OUTPUT(BEEPER);
  1296. if (counterBeep== 0){
  1297. WRITE(BEEPER,HIGH);
  1298. }
  1299. if (counterBeep== 20){
  1300. WRITE(BEEPER,LOW);
  1301. }
  1302. counterBeep++;
  1303. #else
  1304. #if !defined(LCD_FEEDBACK_FREQUENCY_HZ) || !defined(LCD_FEEDBACK_FREQUENCY_DURATION_MS)
  1305. lcd_buzz(1000/6,100);
  1306. #else
  1307. lcd_buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS,LCD_FEEDBACK_FREQUENCY_HZ);
  1308. #endif
  1309. #endif
  1310. }
  1311. }
  1312. WRITE(BEEPER,LOW);
  1313. target[E_AXIS]+= FILAMENTCHANGE_FIRSTFEED ;
  1314. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 20, active_extruder);
  1315. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  1316. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  1317. lcd_change_fil_state = 0;
  1318. lcd_loading_filament();
  1319. while ((lcd_change_fil_state == 0)||(lcd_change_fil_state != 1)){
  1320. lcd_change_fil_state = 0;
  1321. lcd_alright();
  1322. switch(lcd_change_fil_state){
  1323. case 2:
  1324. target[E_AXIS]+= FILAMENTCHANGE_FIRSTFEED ;
  1325. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 20, active_extruder);
  1326. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  1327. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  1328. lcd_loading_filament();
  1329. break;
  1330. case 3:
  1331. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  1332. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  1333. lcd_loading_color();
  1334. break;
  1335. default:
  1336. lcd_change_success();
  1337. break;
  1338. }
  1339. }
  1340. target[E_AXIS]+= 5;
  1341. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  1342. target[E_AXIS]+= FILAMENTCHANGE_FIRSTRETRACT;
  1343. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 400, active_extruder);
  1344. //current_position[E_AXIS]=target[E_AXIS]; //the long retract of L is compensated by manual filament feeding
  1345. //plan_set_e_position(current_position[E_AXIS]);
  1346. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 70, active_extruder); //should do nothing
  1347. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], target[Z_AXIS], target[E_AXIS], 70, active_extruder); //move xy back
  1348. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], target[E_AXIS], 200, active_extruder); //move z back
  1349. target[E_AXIS]= target[E_AXIS] - FILAMENTCHANGE_FIRSTRETRACT;
  1350. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], target[E_AXIS], 5, active_extruder); //final untretract
  1351. plan_set_e_position(lastpos[E_AXIS]);
  1352. feedmultiply=feedmultiplyBckp;
  1353. char cmd[9];
  1354. sprintf_P(cmd, PSTR("M220 S%i"), feedmultiplyBckp);
  1355. enquecommand(cmd);
  1356. }
  1357. #endif
  1358. get_coordinates(); // For X Y Z E F
  1359. #ifdef FWRETRACT
  1360. if(autoretract_enabled)
  1361. if( !(code_seen('X') || code_seen('Y') || code_seen('Z')) && code_seen('E')) {
  1362. float echange=destination[E_AXIS]-current_position[E_AXIS];
  1363. if((echange<-MIN_RETRACT && !retracted) || (echange>MIN_RETRACT && retracted)) { //move appears to be an attempt to retract or recover
  1364. current_position[E_AXIS] = destination[E_AXIS]; //hide the slicer-generated retract/recover from calculations
  1365. plan_set_e_position(current_position[E_AXIS]); //AND from the planner
  1366. retract(!retracted);
  1367. return;
  1368. }
  1369. }
  1370. #endif //FWRETRACT
  1371. prepare_move();
  1372. //ClearToSend();
  1373. }
  1374. break;
  1375. #ifndef SCARA //disable arc support
  1376. case 2: // G2 - CW ARC
  1377. if(Stopped == false) {
  1378. get_arc_coordinates();
  1379. prepare_arc_move(true);
  1380. }
  1381. break;
  1382. case 3: // G3 - CCW ARC
  1383. if(Stopped == false) {
  1384. get_arc_coordinates();
  1385. prepare_arc_move(false);
  1386. }
  1387. break;
  1388. #endif
  1389. case 4: // G4 dwell
  1390. LCD_MESSAGERPGM(MSG_DWELL);
  1391. codenum = 0;
  1392. if(code_seen('P')) codenum = code_value(); // milliseconds to wait
  1393. if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait
  1394. st_synchronize();
  1395. codenum += millis(); // keep track of when we started waiting
  1396. previous_millis_cmd = millis();
  1397. while(millis() < codenum) {
  1398. manage_heater();
  1399. manage_inactivity();
  1400. lcd_update();
  1401. }
  1402. break;
  1403. #ifdef FWRETRACT
  1404. case 10: // G10 retract
  1405. #if EXTRUDERS > 1
  1406. retracted_swap[active_extruder]=(code_seen('S') && code_value_long() == 1); // checks for swap retract argument
  1407. retract(true,retracted_swap[active_extruder]);
  1408. #else
  1409. retract(true);
  1410. #endif
  1411. break;
  1412. case 11: // G11 retract_recover
  1413. #if EXTRUDERS > 1
  1414. retract(false,retracted_swap[active_extruder]);
  1415. #else
  1416. retract(false);
  1417. #endif
  1418. break;
  1419. #endif //FWRETRACT
  1420. case 28: //G28 Home all Axis one at a time
  1421. #ifdef ENABLE_AUTO_BED_LEVELING
  1422. plan_bed_level_matrix.set_to_identity(); //Reset the plane ("erase" all leveling data)
  1423. #endif //ENABLE_AUTO_BED_LEVELING
  1424. saved_feedrate = feedrate;
  1425. saved_feedmultiply = feedmultiply;
  1426. feedmultiply = 100;
  1427. previous_millis_cmd = millis();
  1428. enable_endstops(true);
  1429. for(int8_t i=0; i < NUM_AXIS; i++) {
  1430. destination[i] = current_position[i];
  1431. }
  1432. feedrate = 0.0;
  1433. #ifdef DELTA
  1434. // A delta can only safely home all axis at the same time
  1435. // all axis have to home at the same time
  1436. // Move all carriages up together until the first endstop is hit.
  1437. current_position[X_AXIS] = 0;
  1438. current_position[Y_AXIS] = 0;
  1439. current_position[Z_AXIS] = 0;
  1440. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1441. destination[X_AXIS] = 3 * Z_MAX_LENGTH;
  1442. destination[Y_AXIS] = 3 * Z_MAX_LENGTH;
  1443. destination[Z_AXIS] = 3 * Z_MAX_LENGTH;
  1444. feedrate = 1.732 * homing_feedrate[X_AXIS];
  1445. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1446. st_synchronize();
  1447. endstops_hit_on_purpose();
  1448. current_position[X_AXIS] = destination[X_AXIS];
  1449. current_position[Y_AXIS] = destination[Y_AXIS];
  1450. current_position[Z_AXIS] = destination[Z_AXIS];
  1451. // take care of back off and rehome now we are all at the top
  1452. HOMEAXIS(X);
  1453. HOMEAXIS(Y);
  1454. HOMEAXIS(Z);
  1455. calculate_delta(current_position);
  1456. plan_set_position(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS]);
  1457. #else // NOT DELTA
  1458. home_all_axis = !((code_seen(axis_codes[X_AXIS])) || (code_seen(axis_codes[Y_AXIS])) || (code_seen(axis_codes[Z_AXIS])));
  1459. #if Z_HOME_DIR > 0 // If homing away from BED do Z first
  1460. if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
  1461. HOMEAXIS(Z);
  1462. }
  1463. #endif
  1464. #ifdef QUICK_HOME
  1465. if((home_all_axis)||( code_seen(axis_codes[X_AXIS]) && code_seen(axis_codes[Y_AXIS])) ) //first diagonal move
  1466. {
  1467. current_position[X_AXIS] = 0;current_position[Y_AXIS] = 0;
  1468. #ifndef DUAL_X_CARRIAGE
  1469. int x_axis_home_dir = home_dir(X_AXIS);
  1470. #else
  1471. int x_axis_home_dir = x_home_dir(active_extruder);
  1472. extruder_duplication_enabled = false;
  1473. #endif
  1474. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1475. destination[X_AXIS] = 1.5 * max_length(X_AXIS) * x_axis_home_dir;destination[Y_AXIS] = 1.5 * max_length(Y_AXIS) * home_dir(Y_AXIS);
  1476. feedrate = homing_feedrate[X_AXIS];
  1477. if(homing_feedrate[Y_AXIS]<feedrate)
  1478. feedrate = homing_feedrate[Y_AXIS];
  1479. if (max_length(X_AXIS) > max_length(Y_AXIS)) {
  1480. feedrate *= sqrt(pow(max_length(Y_AXIS) / max_length(X_AXIS), 2) + 1);
  1481. } else {
  1482. feedrate *= sqrt(pow(max_length(X_AXIS) / max_length(Y_AXIS), 2) + 1);
  1483. }
  1484. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1485. st_synchronize();
  1486. axis_is_at_home(X_AXIS);
  1487. axis_is_at_home(Y_AXIS);
  1488. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1489. destination[X_AXIS] = current_position[X_AXIS];
  1490. destination[Y_AXIS] = current_position[Y_AXIS];
  1491. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1492. feedrate = 0.0;
  1493. st_synchronize();
  1494. endstops_hit_on_purpose();
  1495. current_position[X_AXIS] = destination[X_AXIS];
  1496. current_position[Y_AXIS] = destination[Y_AXIS];
  1497. #ifndef SCARA
  1498. current_position[Z_AXIS] = destination[Z_AXIS];
  1499. #endif
  1500. }
  1501. #endif
  1502. if((home_all_axis) || (code_seen(axis_codes[X_AXIS])))
  1503. {
  1504. #ifdef DUAL_X_CARRIAGE
  1505. int tmp_extruder = active_extruder;
  1506. extruder_duplication_enabled = false;
  1507. active_extruder = !active_extruder;
  1508. HOMEAXIS(X);
  1509. inactive_extruder_x_pos = current_position[X_AXIS];
  1510. active_extruder = tmp_extruder;
  1511. HOMEAXIS(X);
  1512. // reset state used by the different modes
  1513. memcpy(raised_parked_position, current_position, sizeof(raised_parked_position));
  1514. delayed_move_time = 0;
  1515. active_extruder_parked = true;
  1516. #else
  1517. HOMEAXIS(X);
  1518. #endif
  1519. }
  1520. if((home_all_axis) || (code_seen(axis_codes[Y_AXIS]))) {
  1521. HOMEAXIS(Y);
  1522. }
  1523. if(code_seen(axis_codes[X_AXIS]))
  1524. {
  1525. if(code_value_long() != 0) {
  1526. #ifdef SCARA
  1527. current_position[X_AXIS]=code_value();
  1528. #else
  1529. current_position[X_AXIS]=code_value()+add_homing[X_AXIS];
  1530. #endif
  1531. }
  1532. }
  1533. if(code_seen(axis_codes[Y_AXIS])) {
  1534. if(code_value_long() != 0) {
  1535. #ifdef SCARA
  1536. current_position[Y_AXIS]=code_value();
  1537. #else
  1538. current_position[Y_AXIS]=code_value()+add_homing[Y_AXIS];
  1539. #endif
  1540. }
  1541. }
  1542. #if Z_HOME_DIR < 0 // If homing towards BED do Z last
  1543. #ifndef Z_SAFE_HOMING
  1544. if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
  1545. #if defined (Z_RAISE_BEFORE_HOMING) && (Z_RAISE_BEFORE_HOMING > 0)
  1546. destination[Z_AXIS] = Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS) * (-1); // Set destination away from bed
  1547. feedrate = max_feedrate[Z_AXIS];
  1548. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
  1549. st_synchronize();
  1550. #endif
  1551. HOMEAXIS(Z);
  1552. }
  1553. #else // Z Safe mode activated.
  1554. if(home_all_axis) {
  1555. destination[X_AXIS] = round(Z_SAFE_HOMING_X_POINT - X_PROBE_OFFSET_FROM_EXTRUDER);
  1556. destination[Y_AXIS] = round(Z_SAFE_HOMING_Y_POINT - Y_PROBE_OFFSET_FROM_EXTRUDER);
  1557. destination[Z_AXIS] = Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS) * (-1); // Set destination away from bed
  1558. feedrate = XY_TRAVEL_SPEED/60;
  1559. current_position[Z_AXIS] = 0;
  1560. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1561. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
  1562. st_synchronize();
  1563. current_position[X_AXIS] = destination[X_AXIS];
  1564. current_position[Y_AXIS] = destination[Y_AXIS];
  1565. HOMEAXIS(Z);
  1566. }
  1567. // Let's see if X and Y are homed and probe is inside bed area.
  1568. if(code_seen(axis_codes[Z_AXIS])) {
  1569. if ( (axis_known_position[X_AXIS]) && (axis_known_position[Y_AXIS]) \
  1570. && (current_position[X_AXIS]+X_PROBE_OFFSET_FROM_EXTRUDER >= X_MIN_POS) \
  1571. && (current_position[X_AXIS]+X_PROBE_OFFSET_FROM_EXTRUDER <= X_MAX_POS) \
  1572. && (current_position[Y_AXIS]+Y_PROBE_OFFSET_FROM_EXTRUDER >= Y_MIN_POS) \
  1573. && (current_position[Y_AXIS]+Y_PROBE_OFFSET_FROM_EXTRUDER <= Y_MAX_POS)) {
  1574. current_position[Z_AXIS] = 0;
  1575. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1576. destination[Z_AXIS] = Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS) * (-1); // Set destination away from bed
  1577. feedrate = max_feedrate[Z_AXIS];
  1578. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
  1579. st_synchronize();
  1580. HOMEAXIS(Z);
  1581. } else if (!((axis_known_position[X_AXIS]) && (axis_known_position[Y_AXIS]))) {
  1582. LCD_MESSAGERPGM(MSG_POSITION_UNKNOWN);
  1583. SERIAL_ECHO_START;
  1584. SERIAL_ECHOLNRPGM(MSG_POSITION_UNKNOWN);
  1585. } else {
  1586. LCD_MESSAGERPGM(MSG_ZPROBE_OUT);
  1587. SERIAL_ECHO_START;
  1588. SERIAL_ECHOLNRPGM(MSG_ZPROBE_OUT);
  1589. }
  1590. }
  1591. #endif
  1592. #endif
  1593. if(code_seen(axis_codes[Z_AXIS])) {
  1594. if(code_value_long() != 0) {
  1595. current_position[Z_AXIS]=code_value()+add_homing[Z_AXIS];
  1596. }
  1597. }
  1598. #ifdef ENABLE_AUTO_BED_LEVELING
  1599. if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
  1600. current_position[Z_AXIS] += zprobe_zoffset; //Add Z_Probe offset (the distance is negative)
  1601. }
  1602. #endif
  1603. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1604. #endif // else DELTA
  1605. #ifdef SCARA
  1606. calculate_delta(current_position);
  1607. plan_set_position(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS]);
  1608. #endif // SCARA
  1609. #ifdef ENDSTOPS_ONLY_FOR_HOMING
  1610. enable_endstops(false);
  1611. #endif
  1612. feedrate = saved_feedrate;
  1613. feedmultiply = saved_feedmultiply;
  1614. previous_millis_cmd = millis();
  1615. endstops_hit_on_purpose();
  1616. if(card.sdprinting) {
  1617. EEPROM_read_B(EEPROM_BABYSTEP_Z,&babystepLoad[2]);
  1618. if(babystepLoad[2] != 0){
  1619. lcd_adjust_z();
  1620. }
  1621. }
  1622. break;
  1623. #ifdef ENABLE_AUTO_BED_LEVELING
  1624. case 29: // G29 Detailed Z-Probe, probes the bed at 3 or more points.
  1625. {
  1626. #if Z_MIN_PIN == -1
  1627. #error "You must have a Z_MIN endstop in order to enable Auto Bed Leveling feature!!! Z_MIN_PIN must point to a valid hardware pin."
  1628. #endif
  1629. // Prevent user from running a G29 without first homing in X and Y
  1630. if (! (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS]) )
  1631. {
  1632. LCD_MESSAGERPGM(MSG_POSITION_UNKNOWN);
  1633. SERIAL_ECHO_START;
  1634. SERIAL_ECHOLNRPGM(MSG_POSITION_UNKNOWN);
  1635. break; // abort G29, since we don't know where we are
  1636. }
  1637. #ifdef Z_PROBE_SLED
  1638. dock_sled(false);
  1639. #endif // Z_PROBE_SLED
  1640. st_synchronize();
  1641. // make sure the bed_level_rotation_matrix is identity or the planner will get it incorectly
  1642. //vector_3 corrected_position = plan_get_position_mm();
  1643. //corrected_position.debug("position before G29");
  1644. plan_bed_level_matrix.set_to_identity();
  1645. vector_3 uncorrected_position = plan_get_position();
  1646. //uncorrected_position.debug("position durring G29");
  1647. current_position[X_AXIS] = uncorrected_position.x;
  1648. current_position[Y_AXIS] = uncorrected_position.y;
  1649. current_position[Z_AXIS] = uncorrected_position.z;
  1650. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1651. setup_for_endstop_move();
  1652. feedrate = homing_feedrate[Z_AXIS];
  1653. #ifdef AUTO_BED_LEVELING_GRID
  1654. // probe at the points of a lattice grid
  1655. int xGridSpacing = (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION) / (AUTO_BED_LEVELING_GRID_POINTS-1);
  1656. int yGridSpacing = (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION) / (AUTO_BED_LEVELING_GRID_POINTS-1);
  1657. // solve the plane equation ax + by + d = z
  1658. // A is the matrix with rows [x y 1] for all the probed points
  1659. // B is the vector of the Z positions
  1660. // the normal vector to the plane is formed by the coefficients of the plane equation in the standard form, which is Vx*x+Vy*y+Vz*z+d = 0
  1661. // so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z
  1662. // "A" matrix of the linear system of equations
  1663. double eqnAMatrix[AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS*3];
  1664. // "B" vector of Z points
  1665. double eqnBVector[AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS];
  1666. int probePointCounter = 0;
  1667. bool zig = true;
  1668. for (int yProbe=FRONT_PROBE_BED_POSITION; yProbe <= BACK_PROBE_BED_POSITION; yProbe += yGridSpacing)
  1669. {
  1670. int xProbe, xInc;
  1671. if (zig)
  1672. {
  1673. xProbe = LEFT_PROBE_BED_POSITION;
  1674. //xEnd = RIGHT_PROBE_BED_POSITION;
  1675. xInc = xGridSpacing;
  1676. zig = false;
  1677. } else // zag
  1678. {
  1679. xProbe = RIGHT_PROBE_BED_POSITION;
  1680. //xEnd = LEFT_PROBE_BED_POSITION;
  1681. xInc = -xGridSpacing;
  1682. zig = true;
  1683. }
  1684. for (int xCount=0; xCount < AUTO_BED_LEVELING_GRID_POINTS; xCount++)
  1685. {
  1686. float z_before;
  1687. if (probePointCounter == 0)
  1688. {
  1689. // raise before probing
  1690. z_before = Z_RAISE_BEFORE_PROBING;
  1691. } else
  1692. {
  1693. // raise extruder
  1694. z_before = current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS;
  1695. }
  1696. float measured_z = probe_pt(xProbe, yProbe, z_before);
  1697. eqnBVector[probePointCounter] = measured_z;
  1698. eqnAMatrix[probePointCounter + 0*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = xProbe;
  1699. eqnAMatrix[probePointCounter + 1*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = yProbe;
  1700. eqnAMatrix[probePointCounter + 2*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = 1;
  1701. probePointCounter++;
  1702. xProbe += xInc;
  1703. }
  1704. }
  1705. clean_up_after_endstop_move();
  1706. // solve lsq problem
  1707. double *plane_equation_coefficients = qr_solve(AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS, 3, eqnAMatrix, eqnBVector);
  1708. SERIAL_PROTOCOLPGM("Eqn coefficients: a: ");
  1709. SERIAL_PROTOCOL(plane_equation_coefficients[0]);
  1710. SERIAL_PROTOCOLPGM(" b: ");
  1711. SERIAL_PROTOCOL(plane_equation_coefficients[1]);
  1712. SERIAL_PROTOCOLPGM(" d: ");
  1713. SERIAL_PROTOCOLLN(plane_equation_coefficients[2]);
  1714. set_bed_level_equation_lsq(plane_equation_coefficients);
  1715. free(plane_equation_coefficients);
  1716. #else // AUTO_BED_LEVELING_GRID not defined
  1717. // Probe at 3 arbitrary points
  1718. // probe 1
  1719. float z_at_pt_1 = probe_pt(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, Z_RAISE_BEFORE_PROBING);
  1720. // probe 2
  1721. float z_at_pt_2 = probe_pt(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS);
  1722. // probe 3
  1723. float z_at_pt_3 = probe_pt(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS);
  1724. clean_up_after_endstop_move();
  1725. set_bed_level_equation_3pts(z_at_pt_1, z_at_pt_2, z_at_pt_3);
  1726. #endif // AUTO_BED_LEVELING_GRID
  1727. st_synchronize();
  1728. // The following code correct the Z height difference from z-probe position and hotend tip position.
  1729. // The Z height on homing is measured by Z-Probe, but the probe is quite far from the hotend.
  1730. // When the bed is uneven, this height must be corrected.
  1731. real_z = float(st_get_position(Z_AXIS))/axis_steps_per_unit[Z_AXIS]; //get the real Z (since the auto bed leveling is already correcting the plane)
  1732. x_tmp = current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER;
  1733. y_tmp = current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER;
  1734. z_tmp = current_position[Z_AXIS];
  1735. apply_rotation_xyz(plan_bed_level_matrix, x_tmp, y_tmp, z_tmp); //Apply the correction sending the probe offset
  1736. current_position[Z_AXIS] = z_tmp - real_z + current_position[Z_AXIS]; //The difference is added to current position and sent to planner.
  1737. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1738. #ifdef Z_PROBE_SLED
  1739. dock_sled(true, -SLED_DOCKING_OFFSET); // correct for over travel.
  1740. #endif // Z_PROBE_SLED
  1741. }
  1742. break;
  1743. #ifndef Z_PROBE_SLED
  1744. case 30: // G30 Single Z Probe
  1745. {
  1746. engage_z_probe(); // Engage Z Servo endstop if available
  1747. st_synchronize();
  1748. // TODO: make sure the bed_level_rotation_matrix is identity or the planner will get set incorectly
  1749. setup_for_endstop_move();
  1750. feedrate = homing_feedrate[Z_AXIS];
  1751. run_z_probe();
  1752. SERIAL_PROTOCOLPGM(MSG_BED);
  1753. SERIAL_PROTOCOLPGM(" X: ");
  1754. SERIAL_PROTOCOL(current_position[X_AXIS]);
  1755. SERIAL_PROTOCOLPGM(" Y: ");
  1756. SERIAL_PROTOCOL(current_position[Y_AXIS]);
  1757. SERIAL_PROTOCOLPGM(" Z: ");
  1758. SERIAL_PROTOCOL(current_position[Z_AXIS]);
  1759. SERIAL_PROTOCOLPGM("\n");
  1760. clean_up_after_endstop_move();
  1761. retract_z_probe(); // Retract Z Servo endstop if available
  1762. }
  1763. break;
  1764. #else
  1765. case 31: // dock the sled
  1766. dock_sled(true);
  1767. break;
  1768. case 32: // undock the sled
  1769. dock_sled(false);
  1770. break;
  1771. #endif // Z_PROBE_SLED
  1772. #endif // ENABLE_AUTO_BED_LEVELING
  1773. case 90: // G90
  1774. relative_mode = false;
  1775. break;
  1776. case 91: // G91
  1777. relative_mode = true;
  1778. break;
  1779. case 92: // G92
  1780. if(!code_seen(axis_codes[E_AXIS]))
  1781. st_synchronize();
  1782. for(int8_t i=0; i < NUM_AXIS; i++) {
  1783. if(code_seen(axis_codes[i])) {
  1784. if(i == E_AXIS) {
  1785. current_position[i] = code_value();
  1786. plan_set_e_position(current_position[E_AXIS]);
  1787. }
  1788. else {
  1789. #ifdef SCARA
  1790. if (i == X_AXIS || i == Y_AXIS) {
  1791. current_position[i] = code_value();
  1792. }
  1793. else {
  1794. current_position[i] = code_value()+add_homing[i];
  1795. }
  1796. #else
  1797. current_position[i] = code_value()+add_homing[i];
  1798. #endif
  1799. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1800. }
  1801. }
  1802. }
  1803. break;
  1804. }
  1805. }
  1806. else if(code_seen('M'))
  1807. {
  1808. switch( (int)code_value() )
  1809. {
  1810. #ifdef ULTIPANEL
  1811. case 0: // M0 - Unconditional stop - Wait for user button press on LCD
  1812. case 1: // M1 - Conditional stop - Wait for user button press on LCD
  1813. {
  1814. char *src = strchr_pointer + 2;
  1815. codenum = 0;
  1816. bool hasP = false, hasS = false;
  1817. if (code_seen('P')) {
  1818. codenum = code_value(); // milliseconds to wait
  1819. hasP = codenum > 0;
  1820. }
  1821. if (code_seen('S')) {
  1822. codenum = code_value() * 1000; // seconds to wait
  1823. hasS = codenum > 0;
  1824. }
  1825. starpos = strchr(src, '*');
  1826. if (starpos != NULL) *(starpos) = '\0';
  1827. while (*src == ' ') ++src;
  1828. if (!hasP && !hasS && *src != '\0') {
  1829. lcd_setstatus(src);
  1830. } else {
  1831. LCD_MESSAGERPGM(MSG_USERWAIT);
  1832. }
  1833. lcd_ignore_click();
  1834. st_synchronize();
  1835. previous_millis_cmd = millis();
  1836. if (codenum > 0){
  1837. codenum += millis(); // keep track of when we started waiting
  1838. while(millis() < codenum && !lcd_clicked()){
  1839. manage_heater();
  1840. manage_inactivity();
  1841. lcd_update();
  1842. }
  1843. lcd_ignore_click(false);
  1844. }else{
  1845. if (!lcd_detected())
  1846. break;
  1847. while(!lcd_clicked()){
  1848. manage_heater();
  1849. manage_inactivity();
  1850. lcd_update();
  1851. }
  1852. }
  1853. if (IS_SD_PRINTING)
  1854. LCD_MESSAGERPGM(MSG_RESUMING);
  1855. else
  1856. LCD_MESSAGERPGM(WELCOME_MSG);
  1857. }
  1858. break;
  1859. #endif
  1860. case 17:
  1861. LCD_MESSAGERPGM(MSG_NO_MOVE);
  1862. enable_x();
  1863. enable_y();
  1864. enable_z();
  1865. enable_e0();
  1866. enable_e1();
  1867. enable_e2();
  1868. break;
  1869. #ifdef SDSUPPORT
  1870. case 20: // M20 - list SD card
  1871. SERIAL_PROTOCOLLNRPGM(MSG_BEGIN_FILE_LIST);
  1872. card.ls();
  1873. SERIAL_PROTOCOLLNRPGM(MSG_END_FILE_LIST);
  1874. break;
  1875. case 21: // M21 - init SD card
  1876. card.initsd();
  1877. break;
  1878. case 22: //M22 - release SD card
  1879. card.release();
  1880. break;
  1881. case 23: //M23 - Select file
  1882. starpos = (strchr(strchr_pointer + 4,'*'));
  1883. if(starpos!=NULL)
  1884. *(starpos)='\0';
  1885. card.openFile(strchr_pointer + 4,true);
  1886. break;
  1887. case 24: //M24 - Start SD print
  1888. card.startFileprint();
  1889. starttime=millis();
  1890. break;
  1891. case 25: //M25 - Pause SD print
  1892. card.pauseSDPrint();
  1893. break;
  1894. case 26: //M26 - Set SD index
  1895. if(card.cardOK && code_seen('S')) {
  1896. card.setIndex(code_value_long());
  1897. }
  1898. break;
  1899. case 27: //M27 - Get SD status
  1900. card.getStatus();
  1901. break;
  1902. case 28: //M28 - Start SD write
  1903. starpos = (strchr(strchr_pointer + 4,'*'));
  1904. if(starpos != NULL){
  1905. char* npos = strchr(cmdbuffer[bufindr], 'N');
  1906. strchr_pointer = strchr(npos,' ') + 1;
  1907. *(starpos) = '\0';
  1908. }
  1909. card.openFile(strchr_pointer+4,false);
  1910. break;
  1911. case 29: //M29 - Stop SD write
  1912. //processed in write to file routine above
  1913. //card,saving = false;
  1914. break;
  1915. case 30: //M30 <filename> Delete File
  1916. if (card.cardOK){
  1917. card.closefile();
  1918. starpos = (strchr(strchr_pointer + 4,'*'));
  1919. if(starpos != NULL){
  1920. char* npos = strchr(cmdbuffer[bufindr], 'N');
  1921. strchr_pointer = strchr(npos,' ') + 1;
  1922. *(starpos) = '\0';
  1923. }
  1924. card.removeFile(strchr_pointer + 4);
  1925. }
  1926. break;
  1927. case 32: //M32 - Select file and start SD print
  1928. {
  1929. if(card.sdprinting) {
  1930. st_synchronize();
  1931. }
  1932. starpos = (strchr(strchr_pointer + 4,'*'));
  1933. char* namestartpos = (strchr(strchr_pointer + 4,'!')); //find ! to indicate filename string start.
  1934. if(namestartpos==NULL)
  1935. {
  1936. namestartpos=strchr_pointer + 4; //default name position, 4 letters after the M
  1937. }
  1938. else
  1939. namestartpos++; //to skip the '!'
  1940. if(starpos!=NULL)
  1941. *(starpos)='\0';
  1942. bool call_procedure=(code_seen('P'));
  1943. if(strchr_pointer>namestartpos)
  1944. call_procedure=false; //false alert, 'P' found within filename
  1945. if( card.cardOK )
  1946. {
  1947. card.openFile(namestartpos,true,!call_procedure);
  1948. if(code_seen('S'))
  1949. if(strchr_pointer<namestartpos) //only if "S" is occuring _before_ the filename
  1950. card.setIndex(code_value_long());
  1951. card.startFileprint();
  1952. if(!call_procedure)
  1953. starttime=millis(); //procedure calls count as normal print time.
  1954. }
  1955. } break;
  1956. case 928: //M928 - Start SD write
  1957. starpos = (strchr(strchr_pointer + 5,'*'));
  1958. if(starpos != NULL){
  1959. char* npos = strchr(cmdbuffer[bufindr], 'N');
  1960. strchr_pointer = strchr(npos,' ') + 1;
  1961. *(starpos) = '\0';
  1962. }
  1963. card.openLogFile(strchr_pointer+5);
  1964. break;
  1965. #endif //SDSUPPORT
  1966. case 31: //M31 take time since the start of the SD print or an M109 command
  1967. {
  1968. stoptime=millis();
  1969. char time[30];
  1970. unsigned long t=(stoptime-starttime)/1000;
  1971. int sec,min;
  1972. min=t/60;
  1973. sec=t%60;
  1974. sprintf_P(time, PSTR("%i min, %i sec"), min, sec);
  1975. SERIAL_ECHO_START;
  1976. SERIAL_ECHOLN(time);
  1977. lcd_setstatus(time);
  1978. autotempShutdown();
  1979. }
  1980. break;
  1981. case 42: //M42 -Change pin status via gcode
  1982. if (code_seen('S'))
  1983. {
  1984. int pin_status = code_value();
  1985. int pin_number = LED_PIN;
  1986. if (code_seen('P') && pin_status >= 0 && pin_status <= 255)
  1987. pin_number = code_value();
  1988. for(int8_t i = 0; i < (int8_t)(sizeof(sensitive_pins)/sizeof(int)); i++)
  1989. {
  1990. if (sensitive_pins[i] == pin_number)
  1991. {
  1992. pin_number = -1;
  1993. break;
  1994. }
  1995. }
  1996. #if defined(FAN_PIN) && FAN_PIN > -1
  1997. if (pin_number == FAN_PIN)
  1998. fanSpeed = pin_status;
  1999. #endif
  2000. if (pin_number > -1)
  2001. {
  2002. pinMode(pin_number, OUTPUT);
  2003. digitalWrite(pin_number, pin_status);
  2004. analogWrite(pin_number, pin_status);
  2005. }
  2006. }
  2007. break;
  2008. // M48 Z-Probe repeatability measurement function.
  2009. //
  2010. // Usage: M48 <n #_samples> <X X_position_for_samples> <Y Y_position_for_samples> <V Verbose_Level> <Engage_probe_for_each_reading> <L legs_of_movement_prior_to_doing_probe>
  2011. //
  2012. // This function assumes the bed has been homed. Specificaly, that a G28 command
  2013. // as been issued prior to invoking the M48 Z-Probe repeatability measurement function.
  2014. // Any information generated by a prior G29 Bed leveling command will be lost and need to be
  2015. // regenerated.
  2016. //
  2017. // The number of samples will default to 10 if not specified. You can use upper or lower case
  2018. // letters for any of the options EXCEPT n. n must be in lower case because Marlin uses a capital
  2019. // N for its communication protocol and will get horribly confused if you send it a capital N.
  2020. //
  2021. #ifdef ENABLE_AUTO_BED_LEVELING
  2022. #ifdef Z_PROBE_REPEATABILITY_TEST
  2023. case 48: // M48 Z-Probe repeatability
  2024. {
  2025. #if Z_MIN_PIN == -1
  2026. #error "You must have a Z_MIN endstop in order to enable calculation of Z-Probe repeatability."
  2027. #endif
  2028. double sum=0.0;
  2029. double mean=0.0;
  2030. double sigma=0.0;
  2031. double sample_set[50];
  2032. int verbose_level=1, n=0, j, n_samples = 10, n_legs=0, engage_probe_for_each_reading=0 ;
  2033. double X_current, Y_current, Z_current;
  2034. double X_probe_location, Y_probe_location, Z_start_location, ext_position;
  2035. if (code_seen('V') || code_seen('v')) {
  2036. verbose_level = code_value();
  2037. if (verbose_level<0 || verbose_level>4 ) {
  2038. SERIAL_PROTOCOLPGM("?Verbose Level not plausable.\n");
  2039. goto Sigma_Exit;
  2040. }
  2041. }
  2042. if (verbose_level > 0) {
  2043. SERIAL_PROTOCOLPGM("M48 Z-Probe Repeatability test. Version 2.00\n");
  2044. SERIAL_PROTOCOLPGM("Full support at: http://3dprintboard.com/forum.php\n");
  2045. }
  2046. if (code_seen('n')) {
  2047. n_samples = code_value();
  2048. if (n_samples<4 || n_samples>50 ) {
  2049. SERIAL_PROTOCOLPGM("?Specified sample size not plausable.\n");
  2050. goto Sigma_Exit;
  2051. }
  2052. }
  2053. X_current = X_probe_location = st_get_position_mm(X_AXIS);
  2054. Y_current = Y_probe_location = st_get_position_mm(Y_AXIS);
  2055. Z_current = st_get_position_mm(Z_AXIS);
  2056. Z_start_location = st_get_position_mm(Z_AXIS) + Z_RAISE_BEFORE_PROBING;
  2057. ext_position = st_get_position_mm(E_AXIS);
  2058. if (code_seen('E') || code_seen('e') )
  2059. engage_probe_for_each_reading++;
  2060. if (code_seen('X') || code_seen('x') ) {
  2061. X_probe_location = code_value() - X_PROBE_OFFSET_FROM_EXTRUDER;
  2062. if (X_probe_location<X_MIN_POS || X_probe_location>X_MAX_POS ) {
  2063. SERIAL_PROTOCOLPGM("?Specified X position out of range.\n");
  2064. goto Sigma_Exit;
  2065. }
  2066. }
  2067. if (code_seen('Y') || code_seen('y') ) {
  2068. Y_probe_location = code_value() - Y_PROBE_OFFSET_FROM_EXTRUDER;
  2069. if (Y_probe_location<Y_MIN_POS || Y_probe_location>Y_MAX_POS ) {
  2070. SERIAL_PROTOCOLPGM("?Specified Y position out of range.\n");
  2071. goto Sigma_Exit;
  2072. }
  2073. }
  2074. if (code_seen('L') || code_seen('l') ) {
  2075. n_legs = code_value();
  2076. if ( n_legs==1 )
  2077. n_legs = 2;
  2078. if ( n_legs<0 || n_legs>15 ) {
  2079. SERIAL_PROTOCOLPGM("?Specified number of legs in movement not plausable.\n");
  2080. goto Sigma_Exit;
  2081. }
  2082. }
  2083. //
  2084. // Do all the preliminary setup work. First raise the probe.
  2085. //
  2086. st_synchronize();
  2087. plan_bed_level_matrix.set_to_identity();
  2088. plan_buffer_line( X_current, Y_current, Z_start_location,
  2089. ext_position,
  2090. homing_feedrate[Z_AXIS]/60,
  2091. active_extruder);
  2092. st_synchronize();
  2093. //
  2094. // Now get everything to the specified probe point So we can safely do a probe to
  2095. // get us close to the bed. If the Z-Axis is far from the bed, we don't want to
  2096. // use that as a starting point for each probe.
  2097. //
  2098. if (verbose_level > 2)
  2099. SERIAL_PROTOCOL("Positioning probe for the test.\n");
  2100. plan_buffer_line( X_probe_location, Y_probe_location, Z_start_location,
  2101. ext_position,
  2102. homing_feedrate[X_AXIS]/60,
  2103. active_extruder);
  2104. st_synchronize();
  2105. current_position[X_AXIS] = X_current = st_get_position_mm(X_AXIS);
  2106. current_position[Y_AXIS] = Y_current = st_get_position_mm(Y_AXIS);
  2107. current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS);
  2108. current_position[E_AXIS] = ext_position = st_get_position_mm(E_AXIS);
  2109. //
  2110. // OK, do the inital probe to get us close to the bed.
  2111. // Then retrace the right amount and use that in subsequent probes
  2112. //
  2113. engage_z_probe();
  2114. setup_for_endstop_move();
  2115. run_z_probe();
  2116. current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS);
  2117. Z_start_location = st_get_position_mm(Z_AXIS) + Z_RAISE_BEFORE_PROBING;
  2118. plan_buffer_line( X_probe_location, Y_probe_location, Z_start_location,
  2119. ext_position,
  2120. homing_feedrate[X_AXIS]/60,
  2121. active_extruder);
  2122. st_synchronize();
  2123. current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS);
  2124. if (engage_probe_for_each_reading)
  2125. retract_z_probe();
  2126. for( n=0; n<n_samples; n++) {
  2127. do_blocking_move_to( X_probe_location, Y_probe_location, Z_start_location); // Make sure we are at the probe location
  2128. if ( n_legs) {
  2129. double radius=0.0, theta=0.0, x_sweep, y_sweep;
  2130. int rotational_direction, l;
  2131. rotational_direction = (unsigned long) millis() & 0x0001; // clockwise or counter clockwise
  2132. radius = (unsigned long) millis() % (long) (X_MAX_LENGTH/4); // limit how far out to go
  2133. theta = (float) ((unsigned long) millis() % (long) 360) / (360./(2*3.1415926)); // turn into radians
  2134. //SERIAL_ECHOPAIR("starting radius: ",radius);
  2135. //SERIAL_ECHOPAIR(" theta: ",theta);
  2136. //SERIAL_ECHOPAIR(" direction: ",rotational_direction);
  2137. //SERIAL_PROTOCOLLNPGM("");
  2138. for( l=0; l<n_legs-1; l++) {
  2139. if (rotational_direction==1)
  2140. theta += (float) ((unsigned long) millis() % (long) 20) / (360.0/(2*3.1415926)); // turn into radians
  2141. else
  2142. theta -= (float) ((unsigned long) millis() % (long) 20) / (360.0/(2*3.1415926)); // turn into radians
  2143. radius += (float) ( ((long) ((unsigned long) millis() % (long) 10)) - 5);
  2144. if ( radius<0.0 )
  2145. radius = -radius;
  2146. X_current = X_probe_location + cos(theta) * radius;
  2147. Y_current = Y_probe_location + sin(theta) * radius;
  2148. if ( X_current<X_MIN_POS) // Make sure our X & Y are sane
  2149. X_current = X_MIN_POS;
  2150. if ( X_current>X_MAX_POS)
  2151. X_current = X_MAX_POS;
  2152. if ( Y_current<Y_MIN_POS) // Make sure our X & Y are sane
  2153. Y_current = Y_MIN_POS;
  2154. if ( Y_current>Y_MAX_POS)
  2155. Y_current = Y_MAX_POS;
  2156. if (verbose_level>3 ) {
  2157. SERIAL_ECHOPAIR("x: ", X_current);
  2158. SERIAL_ECHOPAIR("y: ", Y_current);
  2159. SERIAL_PROTOCOLLNPGM("");
  2160. }
  2161. do_blocking_move_to( X_current, Y_current, Z_current );
  2162. }
  2163. do_blocking_move_to( X_probe_location, Y_probe_location, Z_start_location); // Go back to the probe location
  2164. }
  2165. if (engage_probe_for_each_reading) {
  2166. engage_z_probe();
  2167. delay(1000);
  2168. }
  2169. setup_for_endstop_move();
  2170. run_z_probe();
  2171. sample_set[n] = current_position[Z_AXIS];
  2172. //
  2173. // Get the current mean for the data points we have so far
  2174. //
  2175. sum=0.0;
  2176. for( j=0; j<=n; j++) {
  2177. sum = sum + sample_set[j];
  2178. }
  2179. mean = sum / (double (n+1));
  2180. //
  2181. // Now, use that mean to calculate the standard deviation for the
  2182. // data points we have so far
  2183. //
  2184. sum=0.0;
  2185. for( j=0; j<=n; j++) {
  2186. sum = sum + (sample_set[j]-mean) * (sample_set[j]-mean);
  2187. }
  2188. sigma = sqrt( sum / (double (n+1)) );
  2189. if (verbose_level > 1) {
  2190. SERIAL_PROTOCOL(n+1);
  2191. SERIAL_PROTOCOL(" of ");
  2192. SERIAL_PROTOCOL(n_samples);
  2193. SERIAL_PROTOCOLPGM(" z: ");
  2194. SERIAL_PROTOCOL_F(current_position[Z_AXIS], 6);
  2195. }
  2196. if (verbose_level > 2) {
  2197. SERIAL_PROTOCOL(" mean: ");
  2198. SERIAL_PROTOCOL_F(mean,6);
  2199. SERIAL_PROTOCOL(" sigma: ");
  2200. SERIAL_PROTOCOL_F(sigma,6);
  2201. }
  2202. if (verbose_level > 0)
  2203. SERIAL_PROTOCOLPGM("\n");
  2204. plan_buffer_line( X_probe_location, Y_probe_location, Z_start_location,
  2205. current_position[E_AXIS], homing_feedrate[Z_AXIS]/60, active_extruder);
  2206. st_synchronize();
  2207. if (engage_probe_for_each_reading) {
  2208. retract_z_probe();
  2209. delay(1000);
  2210. }
  2211. }
  2212. retract_z_probe();
  2213. delay(1000);
  2214. clean_up_after_endstop_move();
  2215. // enable_endstops(true);
  2216. if (verbose_level > 0) {
  2217. SERIAL_PROTOCOLPGM("Mean: ");
  2218. SERIAL_PROTOCOL_F(mean, 6);
  2219. SERIAL_PROTOCOLPGM("\n");
  2220. }
  2221. SERIAL_PROTOCOLPGM("Standard Deviation: ");
  2222. SERIAL_PROTOCOL_F(sigma, 6);
  2223. SERIAL_PROTOCOLPGM("\n\n");
  2224. Sigma_Exit:
  2225. break;
  2226. }
  2227. #endif // Z_PROBE_REPEATABILITY_TEST
  2228. #endif // ENABLE_AUTO_BED_LEVELING
  2229. case 104: // M104
  2230. if(setTargetedHotend(104)){
  2231. break;
  2232. }
  2233. if (code_seen('S')) setTargetHotend(code_value(), tmp_extruder);
  2234. #ifdef DUAL_X_CARRIAGE
  2235. if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && tmp_extruder == 0)
  2236. setTargetHotend1(code_value() == 0.0 ? 0.0 : code_value() + duplicate_extruder_temp_offset);
  2237. #endif
  2238. setWatch();
  2239. break;
  2240. case 112: // M112 -Emergency Stop
  2241. kill();
  2242. break;
  2243. case 140: // M140 set bed temp
  2244. if (code_seen('S')) setTargetBed(code_value());
  2245. break;
  2246. case 105 : // M105
  2247. if(setTargetedHotend(105)){
  2248. break;
  2249. }
  2250. #if defined(TEMP_0_PIN) && TEMP_0_PIN > -1
  2251. SERIAL_PROTOCOLPGM("ok T:");
  2252. SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
  2253. SERIAL_PROTOCOLPGM(" /");
  2254. SERIAL_PROTOCOL_F(degTargetHotend(tmp_extruder),1);
  2255. #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
  2256. SERIAL_PROTOCOLPGM(" B:");
  2257. SERIAL_PROTOCOL_F(degBed(),1);
  2258. SERIAL_PROTOCOLPGM(" /");
  2259. SERIAL_PROTOCOL_F(degTargetBed(),1);
  2260. #endif //TEMP_BED_PIN
  2261. for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
  2262. SERIAL_PROTOCOLPGM(" T");
  2263. SERIAL_PROTOCOL(cur_extruder);
  2264. SERIAL_PROTOCOLPGM(":");
  2265. SERIAL_PROTOCOL_F(degHotend(cur_extruder),1);
  2266. SERIAL_PROTOCOLPGM(" /");
  2267. SERIAL_PROTOCOL_F(degTargetHotend(cur_extruder),1);
  2268. }
  2269. #else
  2270. SERIAL_ERROR_START;
  2271. SERIAL_ERRORLNRPGM(MSG_ERR_NO_THERMISTORS);
  2272. #endif
  2273. SERIAL_PROTOCOLPGM(" @:");
  2274. #ifdef EXTRUDER_WATTS
  2275. SERIAL_PROTOCOL((EXTRUDER_WATTS * getHeaterPower(tmp_extruder))/127);
  2276. SERIAL_PROTOCOLPGM("W");
  2277. #else
  2278. SERIAL_PROTOCOL(getHeaterPower(tmp_extruder));
  2279. #endif
  2280. SERIAL_PROTOCOLPGM(" B@:");
  2281. #ifdef BED_WATTS
  2282. SERIAL_PROTOCOL((BED_WATTS * getHeaterPower(-1))/127);
  2283. SERIAL_PROTOCOLPGM("W");
  2284. #else
  2285. SERIAL_PROTOCOL(getHeaterPower(-1));
  2286. #endif
  2287. #ifdef SHOW_TEMP_ADC_VALUES
  2288. #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
  2289. SERIAL_PROTOCOLPGM(" ADC B:");
  2290. SERIAL_PROTOCOL_F(degBed(),1);
  2291. SERIAL_PROTOCOLPGM("C->");
  2292. SERIAL_PROTOCOL_F(rawBedTemp()/OVERSAMPLENR,0);
  2293. #endif
  2294. for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
  2295. SERIAL_PROTOCOLPGM(" T");
  2296. SERIAL_PROTOCOL(cur_extruder);
  2297. SERIAL_PROTOCOLPGM(":");
  2298. SERIAL_PROTOCOL_F(degHotend(cur_extruder),1);
  2299. SERIAL_PROTOCOLPGM("C->");
  2300. SERIAL_PROTOCOL_F(rawHotendTemp(cur_extruder)/OVERSAMPLENR,0);
  2301. }
  2302. #endif
  2303. SERIAL_PROTOCOLLN("");
  2304. return;
  2305. break;
  2306. case 109:
  2307. {// M109 - Wait for extruder heater to reach target.
  2308. if(setTargetedHotend(109)){
  2309. break;
  2310. }
  2311. LCD_MESSAGERPGM(MSG_HEATING);
  2312. #ifdef AUTOTEMP
  2313. autotemp_enabled=false;
  2314. #endif
  2315. if (code_seen('S')) {
  2316. setTargetHotend(code_value(), tmp_extruder);
  2317. #ifdef DUAL_X_CARRIAGE
  2318. if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && tmp_extruder == 0)
  2319. setTargetHotend1(code_value() == 0.0 ? 0.0 : code_value() + duplicate_extruder_temp_offset);
  2320. #endif
  2321. CooldownNoWait = true;
  2322. } else if (code_seen('R')) {
  2323. setTargetHotend(code_value(), tmp_extruder);
  2324. #ifdef DUAL_X_CARRIAGE
  2325. if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && tmp_extruder == 0)
  2326. setTargetHotend1(code_value() == 0.0 ? 0.0 : code_value() + duplicate_extruder_temp_offset);
  2327. #endif
  2328. CooldownNoWait = false;
  2329. }
  2330. #ifdef AUTOTEMP
  2331. if (code_seen('S')) autotemp_min=code_value();
  2332. if (code_seen('B')) autotemp_max=code_value();
  2333. if (code_seen('F'))
  2334. {
  2335. autotemp_factor=code_value();
  2336. autotemp_enabled=true;
  2337. }
  2338. #endif
  2339. setWatch();
  2340. codenum = millis();
  2341. /* See if we are heating up or cooling down */
  2342. target_direction = isHeatingHotend(tmp_extruder); // true if heating, false if cooling
  2343. cancel_heatup = false;
  2344. #ifdef TEMP_RESIDENCY_TIME
  2345. long residencyStart;
  2346. residencyStart = -1;
  2347. /* continue to loop until we have reached the target temp
  2348. _and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */
  2349. while((!cancel_heatup)&&((residencyStart == -1) ||
  2350. (residencyStart >= 0 && (((unsigned int) (millis() - residencyStart)) < (TEMP_RESIDENCY_TIME * 1000UL)))) ) {
  2351. #else
  2352. while ( target_direction ? (isHeatingHotend(tmp_extruder)) : (isCoolingHotend(tmp_extruder)&&(CooldownNoWait==false)) ) {
  2353. #endif //TEMP_RESIDENCY_TIME
  2354. if( (millis() - codenum) > 1000UL )
  2355. { //Print Temp Reading and remaining time every 1 second while heating up/cooling down
  2356. SERIAL_PROTOCOLPGM("T:");
  2357. SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
  2358. SERIAL_PROTOCOLPGM(" E:");
  2359. SERIAL_PROTOCOL((int)tmp_extruder);
  2360. #ifdef TEMP_RESIDENCY_TIME
  2361. SERIAL_PROTOCOLPGM(" W:");
  2362. if(residencyStart > -1)
  2363. {
  2364. codenum = ((TEMP_RESIDENCY_TIME * 1000UL) - (millis() - residencyStart)) / 1000UL;
  2365. SERIAL_PROTOCOLLN( codenum );
  2366. }
  2367. else
  2368. {
  2369. SERIAL_PROTOCOLLN( "?" );
  2370. }
  2371. #else
  2372. SERIAL_PROTOCOLLN("");
  2373. #endif
  2374. codenum = millis();
  2375. }
  2376. manage_heater();
  2377. manage_inactivity();
  2378. lcd_update();
  2379. #ifdef TEMP_RESIDENCY_TIME
  2380. /* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
  2381. or when current temp falls outside the hysteresis after target temp was reached */
  2382. if ((residencyStart == -1 && target_direction && (degHotend(tmp_extruder) >= (degTargetHotend(tmp_extruder)-TEMP_WINDOW))) ||
  2383. (residencyStart == -1 && !target_direction && (degHotend(tmp_extruder) <= (degTargetHotend(tmp_extruder)+TEMP_WINDOW))) ||
  2384. (residencyStart > -1 && labs(degHotend(tmp_extruder) - degTargetHotend(tmp_extruder)) > TEMP_HYSTERESIS) )
  2385. {
  2386. residencyStart = millis();
  2387. }
  2388. #endif //TEMP_RESIDENCY_TIME
  2389. }
  2390. LCD_MESSAGERPGM(MSG_HEATING_COMPLETE);
  2391. if(IS_SD_PRINTING){
  2392. lcd_setstatus("SD-PRINTING ");
  2393. }
  2394. starttime=millis();
  2395. previous_millis_cmd = millis();
  2396. }
  2397. break;
  2398. case 190: // M190 - Wait for bed heater to reach target.
  2399. #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
  2400. LCD_MESSAGERPGM(MSG_BED_HEATING);
  2401. if (code_seen('S')) {
  2402. setTargetBed(code_value());
  2403. CooldownNoWait = true;
  2404. } else if (code_seen('R')) {
  2405. setTargetBed(code_value());
  2406. CooldownNoWait = false;
  2407. }
  2408. codenum = millis();
  2409. cancel_heatup = false;
  2410. target_direction = isHeatingBed(); // true if heating, false if cooling
  2411. while ( (target_direction)&&(!cancel_heatup) ? (isHeatingBed()) : (isCoolingBed()&&(CooldownNoWait==false)) )
  2412. {
  2413. if(( millis() - codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
  2414. {
  2415. float tt=degHotend(active_extruder);
  2416. SERIAL_PROTOCOLPGM("T:");
  2417. SERIAL_PROTOCOL(tt);
  2418. SERIAL_PROTOCOLPGM(" E:");
  2419. SERIAL_PROTOCOL((int)active_extruder);
  2420. SERIAL_PROTOCOLPGM(" B:");
  2421. SERIAL_PROTOCOL_F(degBed(),1);
  2422. SERIAL_PROTOCOLLN("");
  2423. codenum = millis();
  2424. }
  2425. manage_heater();
  2426. manage_inactivity();
  2427. lcd_update();
  2428. }
  2429. LCD_MESSAGERPGM(MSG_BED_DONE);
  2430. if(IS_SD_PRINTING){
  2431. lcd_setstatus("SD-PRINTING ");
  2432. }
  2433. previous_millis_cmd = millis();
  2434. #endif
  2435. break;
  2436. #if defined(FAN_PIN) && FAN_PIN > -1
  2437. case 106: //M106 Fan On
  2438. if (code_seen('S')){
  2439. fanSpeed=constrain(code_value(),0,255);
  2440. }
  2441. else {
  2442. fanSpeed=255;
  2443. }
  2444. break;
  2445. case 107: //M107 Fan Off
  2446. fanSpeed = 0;
  2447. break;
  2448. #endif //FAN_PIN
  2449. #ifdef BARICUDA
  2450. // PWM for HEATER_1_PIN
  2451. #if defined(HEATER_1_PIN) && HEATER_1_PIN > -1
  2452. case 126: //M126 valve open
  2453. if (code_seen('S')){
  2454. ValvePressure=constrain(code_value(),0,255);
  2455. }
  2456. else {
  2457. ValvePressure=255;
  2458. }
  2459. break;
  2460. case 127: //M127 valve closed
  2461. ValvePressure = 0;
  2462. break;
  2463. #endif //HEATER_1_PIN
  2464. // PWM for HEATER_2_PIN
  2465. #if defined(HEATER_2_PIN) && HEATER_2_PIN > -1
  2466. case 128: //M128 valve open
  2467. if (code_seen('S')){
  2468. EtoPPressure=constrain(code_value(),0,255);
  2469. }
  2470. else {
  2471. EtoPPressure=255;
  2472. }
  2473. break;
  2474. case 129: //M129 valve closed
  2475. EtoPPressure = 0;
  2476. break;
  2477. #endif //HEATER_2_PIN
  2478. #endif
  2479. #if defined(PS_ON_PIN) && PS_ON_PIN > -1
  2480. case 80: // M80 - Turn on Power Supply
  2481. SET_OUTPUT(PS_ON_PIN); //GND
  2482. WRITE(PS_ON_PIN, PS_ON_AWAKE);
  2483. // If you have a switch on suicide pin, this is useful
  2484. // if you want to start another print with suicide feature after
  2485. // a print without suicide...
  2486. #if defined SUICIDE_PIN && SUICIDE_PIN > -1
  2487. SET_OUTPUT(SUICIDE_PIN);
  2488. WRITE(SUICIDE_PIN, HIGH);
  2489. #endif
  2490. #ifdef ULTIPANEL
  2491. powersupply = true;
  2492. LCD_MESSAGERPGM(WELCOME_MSG);
  2493. lcd_update();
  2494. #endif
  2495. break;
  2496. #endif
  2497. case 81: // M81 - Turn off Power Supply
  2498. disable_heater();
  2499. st_synchronize();
  2500. disable_e0();
  2501. disable_e1();
  2502. disable_e2();
  2503. finishAndDisableSteppers();
  2504. fanSpeed = 0;
  2505. delay(1000); // Wait a little before to switch off
  2506. #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
  2507. st_synchronize();
  2508. suicide();
  2509. #elif defined(PS_ON_PIN) && PS_ON_PIN > -1
  2510. SET_OUTPUT(PS_ON_PIN);
  2511. WRITE(PS_ON_PIN, PS_ON_ASLEEP);
  2512. #endif
  2513. #ifdef ULTIPANEL
  2514. powersupply = false;
  2515. LCD_MESSAGERPGM(CAT4(MACHINE_NAME,PSTR(" "),MSG_OFF,PSTR("."))); //!!!!!!!!!!!!!!
  2516. /*
  2517. MACHNAME = "Prusa i3"
  2518. MSGOFF = "Vypnuto"
  2519. "Prusai3"" ""vypnuto""."
  2520. "Prusa i3"" "MSG_ALL[lang_selected][50]"."
  2521. */
  2522. lcd_update();
  2523. #endif
  2524. break;
  2525. case 82:
  2526. axis_relative_modes[3] = false;
  2527. break;
  2528. case 83:
  2529. axis_relative_modes[3] = true;
  2530. break;
  2531. case 18: //compatibility
  2532. case 84: // M84
  2533. if(code_seen('S')){
  2534. stepper_inactive_time = code_value() * 1000;
  2535. }
  2536. else
  2537. {
  2538. bool all_axis = !((code_seen(axis_codes[X_AXIS])) || (code_seen(axis_codes[Y_AXIS])) || (code_seen(axis_codes[Z_AXIS]))|| (code_seen(axis_codes[E_AXIS])));
  2539. if(all_axis)
  2540. {
  2541. st_synchronize();
  2542. disable_e0();
  2543. disable_e1();
  2544. disable_e2();
  2545. finishAndDisableSteppers();
  2546. }
  2547. else
  2548. {
  2549. st_synchronize();
  2550. if(code_seen('X')) disable_x();
  2551. if(code_seen('Y')) disable_y();
  2552. if(code_seen('Z')) disable_z();
  2553. #if ((E0_ENABLE_PIN != X_ENABLE_PIN) && (E1_ENABLE_PIN != Y_ENABLE_PIN)) // Only enable on boards that have seperate ENABLE_PINS
  2554. if(code_seen('E')) {
  2555. disable_e0();
  2556. disable_e1();
  2557. disable_e2();
  2558. }
  2559. #endif
  2560. }
  2561. }
  2562. break;
  2563. case 85: // M85
  2564. if(code_seen('S')) {
  2565. max_inactive_time = code_value() * 1000;
  2566. }
  2567. break;
  2568. case 92: // M92
  2569. for(int8_t i=0; i < NUM_AXIS; i++)
  2570. {
  2571. if(code_seen(axis_codes[i]))
  2572. {
  2573. if(i == 3) { // E
  2574. float value = code_value();
  2575. if(value < 20.0) {
  2576. float factor = axis_steps_per_unit[i] / value; // increase e constants if M92 E14 is given for netfab.
  2577. max_e_jerk *= factor;
  2578. max_feedrate[i] *= factor;
  2579. axis_steps_per_sqr_second[i] *= factor;
  2580. }
  2581. axis_steps_per_unit[i] = value;
  2582. }
  2583. else {
  2584. axis_steps_per_unit[i] = code_value();
  2585. }
  2586. }
  2587. }
  2588. break;
  2589. case 115: // M115
  2590. SERIAL_PROTOCOLRPGM(MSG_M115_REPORT);
  2591. break;
  2592. case 117: // M117 display message
  2593. starpos = (strchr(strchr_pointer + 5,'*'));
  2594. if(starpos!=NULL)
  2595. *(starpos)='\0';
  2596. lcd_setstatus(strchr_pointer + 5);
  2597. break;
  2598. case 114: // M114
  2599. SERIAL_PROTOCOLPGM("X:");
  2600. SERIAL_PROTOCOL(current_position[X_AXIS]);
  2601. SERIAL_PROTOCOLPGM(" Y:");
  2602. SERIAL_PROTOCOL(current_position[Y_AXIS]);
  2603. SERIAL_PROTOCOLPGM(" Z:");
  2604. SERIAL_PROTOCOL(current_position[Z_AXIS]);
  2605. SERIAL_PROTOCOLPGM(" E:");
  2606. SERIAL_PROTOCOL(current_position[E_AXIS]);
  2607. SERIAL_PROTOCOLRPGM(MSG_COUNT_X);
  2608. SERIAL_PROTOCOL(float(st_get_position(X_AXIS))/axis_steps_per_unit[X_AXIS]);
  2609. SERIAL_PROTOCOLPGM(" Y:");
  2610. SERIAL_PROTOCOL(float(st_get_position(Y_AXIS))/axis_steps_per_unit[Y_AXIS]);
  2611. SERIAL_PROTOCOLPGM(" Z:");
  2612. SERIAL_PROTOCOL(float(st_get_position(Z_AXIS))/axis_steps_per_unit[Z_AXIS]);
  2613. SERIAL_PROTOCOLLN("");
  2614. #ifdef SCARA
  2615. SERIAL_PROTOCOLPGM("SCARA Theta:");
  2616. SERIAL_PROTOCOL(delta[X_AXIS]);
  2617. SERIAL_PROTOCOLPGM(" Psi+Theta:");
  2618. SERIAL_PROTOCOL(delta[Y_AXIS]);
  2619. SERIAL_PROTOCOLLN("");
  2620. SERIAL_PROTOCOLPGM("SCARA Cal - Theta:");
  2621. SERIAL_PROTOCOL(delta[X_AXIS]+add_homing[X_AXIS]);
  2622. SERIAL_PROTOCOLPGM(" Psi+Theta (90):");
  2623. SERIAL_PROTOCOL(delta[Y_AXIS]-delta[X_AXIS]-90+add_homing[Y_AXIS]);
  2624. SERIAL_PROTOCOLLN("");
  2625. SERIAL_PROTOCOLPGM("SCARA step Cal - Theta:");
  2626. SERIAL_PROTOCOL(delta[X_AXIS]/90*axis_steps_per_unit[X_AXIS]);
  2627. SERIAL_PROTOCOLPGM(" Psi+Theta:");
  2628. SERIAL_PROTOCOL((delta[Y_AXIS]-delta[X_AXIS])/90*axis_steps_per_unit[Y_AXIS]);
  2629. SERIAL_PROTOCOLLN("");
  2630. SERIAL_PROTOCOLLN("");
  2631. #endif
  2632. break;
  2633. case 120: // M120
  2634. enable_endstops(false) ;
  2635. break;
  2636. case 121: // M121
  2637. enable_endstops(true) ;
  2638. break;
  2639. case 119: // M119
  2640. SERIAL_PROTOCOLRPGM(MSG_M119_REPORT);
  2641. SERIAL_PROTOCOLLN("");
  2642. #if defined(X_MIN_PIN) && X_MIN_PIN > -1
  2643. SERIAL_PROTOCOLRPGM(MSG_X_MIN);
  2644. if(READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING){
  2645. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
  2646. }else{
  2647. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
  2648. }
  2649. SERIAL_PROTOCOLLN("");
  2650. #endif
  2651. #if defined(X_MAX_PIN) && X_MAX_PIN > -1
  2652. SERIAL_PROTOCOLRPGM(MSG_X_MAX);
  2653. if(READ(X_MAX_PIN)^X_MAX_ENDSTOP_INVERTING){
  2654. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
  2655. }else{
  2656. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
  2657. }
  2658. SERIAL_PROTOCOLLN("");
  2659. #endif
  2660. #if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
  2661. SERIAL_PROTOCOLRPGM(MSG_Y_MIN);
  2662. if(READ(Y_MIN_PIN)^Y_MIN_ENDSTOP_INVERTING){
  2663. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
  2664. }else{
  2665. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
  2666. }
  2667. SERIAL_PROTOCOLLN("");
  2668. #endif
  2669. #if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
  2670. SERIAL_PROTOCOLRPGM(MSG_Y_MAX);
  2671. if(READ(Y_MAX_PIN)^Y_MAX_ENDSTOP_INVERTING){
  2672. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
  2673. }else{
  2674. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
  2675. }
  2676. SERIAL_PROTOCOLLN("");
  2677. #endif
  2678. #if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
  2679. SERIAL_PROTOCOLRPGM(MSG_Z_MIN);
  2680. if(READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING){
  2681. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
  2682. }else{
  2683. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
  2684. }
  2685. SERIAL_PROTOCOLLN("");
  2686. #endif
  2687. #if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
  2688. SERIAL_PROTOCOLRPGM(MSG_Z_MAX);
  2689. if(READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING){
  2690. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
  2691. }else{
  2692. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
  2693. }
  2694. SERIAL_PROTOCOLLN("");
  2695. #endif
  2696. break;
  2697. //TODO: update for all axis, use for loop
  2698. #ifdef BLINKM
  2699. case 150: // M150
  2700. {
  2701. byte red;
  2702. byte grn;
  2703. byte blu;
  2704. if(code_seen('R')) red = code_value();
  2705. if(code_seen('U')) grn = code_value();
  2706. if(code_seen('B')) blu = code_value();
  2707. SendColors(red,grn,blu);
  2708. }
  2709. break;
  2710. #endif //BLINKM
  2711. case 200: // M200 D<millimeters> set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).
  2712. {
  2713. tmp_extruder = active_extruder;
  2714. if(code_seen('T')) {
  2715. tmp_extruder = code_value();
  2716. if(tmp_extruder >= EXTRUDERS) {
  2717. SERIAL_ECHO_START;
  2718. SERIAL_ECHO(MSG_M200_INVALID_EXTRUDER);
  2719. break;
  2720. }
  2721. }
  2722. float area = .0;
  2723. if(code_seen('D')) {
  2724. float diameter = (float)code_value();
  2725. if (diameter == 0.0) {
  2726. // setting any extruder filament size disables volumetric on the assumption that
  2727. // slicers either generate in extruder values as cubic mm or as as filament feeds
  2728. // for all extruders
  2729. volumetric_enabled = false;
  2730. } else {
  2731. filament_size[tmp_extruder] = (float)code_value();
  2732. // make sure all extruders have some sane value for the filament size
  2733. filament_size[0] = (filament_size[0] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[0]);
  2734. #if EXTRUDERS > 1
  2735. filament_size[1] = (filament_size[1] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[1]);
  2736. #if EXTRUDERS > 2
  2737. filament_size[2] = (filament_size[2] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[2]);
  2738. #endif
  2739. #endif
  2740. volumetric_enabled = true;
  2741. }
  2742. } else {
  2743. //reserved for setting filament diameter via UFID or filament measuring device
  2744. break;
  2745. }
  2746. calculate_volumetric_multipliers();
  2747. }
  2748. break;
  2749. case 201: // M201
  2750. for(int8_t i=0; i < NUM_AXIS; i++)
  2751. {
  2752. if(code_seen(axis_codes[i]))
  2753. {
  2754. max_acceleration_units_per_sq_second[i] = code_value();
  2755. }
  2756. }
  2757. // steps per sq second need to be updated to agree with the units per sq second (as they are what is used in the planner)
  2758. reset_acceleration_rates();
  2759. break;
  2760. #if 0 // Not used for Sprinter/grbl gen6
  2761. case 202: // M202
  2762. for(int8_t i=0; i < NUM_AXIS; i++) {
  2763. if(code_seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i];
  2764. }
  2765. break;
  2766. #endif
  2767. case 203: // M203 max feedrate mm/sec
  2768. for(int8_t i=0; i < NUM_AXIS; i++) {
  2769. if(code_seen(axis_codes[i])) max_feedrate[i] = code_value();
  2770. }
  2771. break;
  2772. case 204: // M204 acclereration S normal moves T filmanent only moves
  2773. {
  2774. if(code_seen('S')) acceleration = code_value() ;
  2775. if(code_seen('T')) retract_acceleration = code_value() ;
  2776. }
  2777. break;
  2778. 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
  2779. {
  2780. if(code_seen('S')) minimumfeedrate = code_value();
  2781. if(code_seen('T')) mintravelfeedrate = code_value();
  2782. if(code_seen('B')) minsegmenttime = code_value() ;
  2783. if(code_seen('X')) max_xy_jerk = code_value() ;
  2784. if(code_seen('Z')) max_z_jerk = code_value() ;
  2785. if(code_seen('E')) max_e_jerk = code_value() ;
  2786. }
  2787. break;
  2788. case 206: // M206 additional homing offset
  2789. for(int8_t i=0; i < 3; i++)
  2790. {
  2791. if(code_seen(axis_codes[i])) add_homing[i] = code_value();
  2792. }
  2793. #ifdef SCARA
  2794. if(code_seen('T')) // Theta
  2795. {
  2796. add_homing[X_AXIS] = code_value() ;
  2797. }
  2798. if(code_seen('P')) // Psi
  2799. {
  2800. add_homing[Y_AXIS] = code_value() ;
  2801. }
  2802. #endif
  2803. break;
  2804. #ifdef DELTA
  2805. case 665: // M665 set delta configurations L<diagonal_rod> R<delta_radius> S<segments_per_sec>
  2806. if(code_seen('L')) {
  2807. delta_diagonal_rod= code_value();
  2808. }
  2809. if(code_seen('R')) {
  2810. delta_radius= code_value();
  2811. }
  2812. if(code_seen('S')) {
  2813. delta_segments_per_second= code_value();
  2814. }
  2815. recalc_delta_settings(delta_radius, delta_diagonal_rod);
  2816. break;
  2817. case 666: // M666 set delta endstop adjustemnt
  2818. for(int8_t i=0; i < 3; i++)
  2819. {
  2820. if(code_seen(axis_codes[i])) endstop_adj[i] = code_value();
  2821. }
  2822. break;
  2823. #endif
  2824. #ifdef FWRETRACT
  2825. case 207: //M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop]
  2826. {
  2827. if(code_seen('S'))
  2828. {
  2829. retract_length = code_value() ;
  2830. }
  2831. if(code_seen('F'))
  2832. {
  2833. retract_feedrate = code_value()/60 ;
  2834. }
  2835. if(code_seen('Z'))
  2836. {
  2837. retract_zlift = code_value() ;
  2838. }
  2839. }break;
  2840. case 208: // M208 - set retract recover length S[positive mm surplus to the M207 S*] F[feedrate mm/min]
  2841. {
  2842. if(code_seen('S'))
  2843. {
  2844. retract_recover_length = code_value() ;
  2845. }
  2846. if(code_seen('F'))
  2847. {
  2848. retract_recover_feedrate = code_value()/60 ;
  2849. }
  2850. }break;
  2851. case 209: // M209 - S<1=true/0=false> enable automatic retract detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction.
  2852. {
  2853. if(code_seen('S'))
  2854. {
  2855. int t= code_value() ;
  2856. switch(t)
  2857. {
  2858. case 0:
  2859. {
  2860. autoretract_enabled=false;
  2861. retracted[0]=false;
  2862. #if EXTRUDERS > 1
  2863. retracted[1]=false;
  2864. #endif
  2865. #if EXTRUDERS > 2
  2866. retracted[2]=false;
  2867. #endif
  2868. }break;
  2869. case 1:
  2870. {
  2871. autoretract_enabled=true;
  2872. retracted[0]=false;
  2873. #if EXTRUDERS > 1
  2874. retracted[1]=false;
  2875. #endif
  2876. #if EXTRUDERS > 2
  2877. retracted[2]=false;
  2878. #endif
  2879. }break;
  2880. default:
  2881. SERIAL_ECHO_START;
  2882. SERIAL_ECHORPGM(MSG_UNKNOWN_COMMAND);
  2883. SERIAL_ECHO(cmdbuffer[bufindr]);
  2884. SERIAL_ECHOLNPGM("\"");
  2885. }
  2886. }
  2887. }break;
  2888. #endif // FWRETRACT
  2889. #if EXTRUDERS > 1
  2890. case 218: // M218 - set hotend offset (in mm), T<extruder_number> X<offset_on_X> Y<offset_on_Y>
  2891. {
  2892. if(setTargetedHotend(218)){
  2893. break;
  2894. }
  2895. if(code_seen('X'))
  2896. {
  2897. extruder_offset[X_AXIS][tmp_extruder] = code_value();
  2898. }
  2899. if(code_seen('Y'))
  2900. {
  2901. extruder_offset[Y_AXIS][tmp_extruder] = code_value();
  2902. }
  2903. #ifdef DUAL_X_CARRIAGE
  2904. if(code_seen('Z'))
  2905. {
  2906. extruder_offset[Z_AXIS][tmp_extruder] = code_value();
  2907. }
  2908. #endif
  2909. SERIAL_ECHO_START;
  2910. SERIAL_ECHORPGM(MSG_HOTEND_OFFSET);
  2911. for(tmp_extruder = 0; tmp_extruder < EXTRUDERS; tmp_extruder++)
  2912. {
  2913. SERIAL_ECHO(" ");
  2914. SERIAL_ECHO(extruder_offset[X_AXIS][tmp_extruder]);
  2915. SERIAL_ECHO(",");
  2916. SERIAL_ECHO(extruder_offset[Y_AXIS][tmp_extruder]);
  2917. #ifdef DUAL_X_CARRIAGE
  2918. SERIAL_ECHO(",");
  2919. SERIAL_ECHO(extruder_offset[Z_AXIS][tmp_extruder]);
  2920. #endif
  2921. }
  2922. SERIAL_ECHOLN("");
  2923. }break;
  2924. #endif
  2925. case 220: // M220 S<factor in percent>- set speed factor override percentage
  2926. {
  2927. if(code_seen('S'))
  2928. {
  2929. feedmultiply = code_value() ;
  2930. }
  2931. }
  2932. break;
  2933. case 221: // M221 S<factor in percent>- set extrude factor override percentage
  2934. {
  2935. if(code_seen('S'))
  2936. {
  2937. int tmp_code = code_value();
  2938. if (code_seen('T'))
  2939. {
  2940. if(setTargetedHotend(221)){
  2941. break;
  2942. }
  2943. extruder_multiply[tmp_extruder] = tmp_code;
  2944. }
  2945. else
  2946. {
  2947. extrudemultiply = tmp_code ;
  2948. }
  2949. }
  2950. }
  2951. break;
  2952. case 226: // M226 P<pin number> S<pin state>- Wait until the specified pin reaches the state required
  2953. {
  2954. if(code_seen('P')){
  2955. int pin_number = code_value(); // pin number
  2956. int pin_state = -1; // required pin state - default is inverted
  2957. if(code_seen('S')) pin_state = code_value(); // required pin state
  2958. if(pin_state >= -1 && pin_state <= 1){
  2959. for(int8_t i = 0; i < (int8_t)(sizeof(sensitive_pins)/sizeof(int)); i++)
  2960. {
  2961. if (sensitive_pins[i] == pin_number)
  2962. {
  2963. pin_number = -1;
  2964. break;
  2965. }
  2966. }
  2967. if (pin_number > -1)
  2968. {
  2969. int target = LOW;
  2970. st_synchronize();
  2971. pinMode(pin_number, INPUT);
  2972. switch(pin_state){
  2973. case 1:
  2974. target = HIGH;
  2975. break;
  2976. case 0:
  2977. target = LOW;
  2978. break;
  2979. case -1:
  2980. target = !digitalRead(pin_number);
  2981. break;
  2982. }
  2983. while(digitalRead(pin_number) != target){
  2984. manage_heater();
  2985. manage_inactivity();
  2986. lcd_update();
  2987. }
  2988. }
  2989. }
  2990. }
  2991. }
  2992. break;
  2993. #if NUM_SERVOS > 0
  2994. case 280: // M280 - set servo position absolute. P: servo index, S: angle or microseconds
  2995. {
  2996. int servo_index = -1;
  2997. int servo_position = 0;
  2998. if (code_seen('P'))
  2999. servo_index = code_value();
  3000. if (code_seen('S')) {
  3001. servo_position = code_value();
  3002. if ((servo_index >= 0) && (servo_index < NUM_SERVOS)) {
  3003. #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
  3004. servos[servo_index].attach(0);
  3005. #endif
  3006. servos[servo_index].write(servo_position);
  3007. #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
  3008. delay(PROBE_SERVO_DEACTIVATION_DELAY);
  3009. servos[servo_index].detach();
  3010. #endif
  3011. }
  3012. else {
  3013. SERIAL_ECHO_START;
  3014. SERIAL_ECHO("Servo ");
  3015. SERIAL_ECHO(servo_index);
  3016. SERIAL_ECHOLN(" out of range");
  3017. }
  3018. }
  3019. else if (servo_index >= 0) {
  3020. SERIAL_PROTOCOL(MSG_OK);
  3021. SERIAL_PROTOCOL(" Servo ");
  3022. SERIAL_PROTOCOL(servo_index);
  3023. SERIAL_PROTOCOL(": ");
  3024. SERIAL_PROTOCOL(servos[servo_index].read());
  3025. SERIAL_PROTOCOLLN("");
  3026. }
  3027. }
  3028. break;
  3029. #endif // NUM_SERVOS > 0
  3030. #if (LARGE_FLASH == true && ( BEEPER > 0 || defined(ULTRALCD) || defined(LCD_USE_I2C_BUZZER)))
  3031. case 300: // M300
  3032. {
  3033. int beepS = code_seen('S') ? code_value() : 110;
  3034. int beepP = code_seen('P') ? code_value() : 1000;
  3035. if (beepS > 0)
  3036. {
  3037. #if BEEPER > 0
  3038. tone(BEEPER, beepS);
  3039. delay(beepP);
  3040. noTone(BEEPER);
  3041. #elif defined(ULTRALCD)
  3042. lcd_buzz(beepS, beepP);
  3043. #elif defined(LCD_USE_I2C_BUZZER)
  3044. lcd_buzz(beepP, beepS);
  3045. #endif
  3046. }
  3047. else
  3048. {
  3049. delay(beepP);
  3050. }
  3051. }
  3052. break;
  3053. #endif // M300
  3054. #ifdef PIDTEMP
  3055. case 301: // M301
  3056. {
  3057. if(code_seen('P')) Kp = code_value();
  3058. if(code_seen('I')) Ki = scalePID_i(code_value());
  3059. if(code_seen('D')) Kd = scalePID_d(code_value());
  3060. #ifdef PID_ADD_EXTRUSION_RATE
  3061. if(code_seen('C')) Kc = code_value();
  3062. #endif
  3063. updatePID();
  3064. SERIAL_PROTOCOL(MSG_OK);
  3065. SERIAL_PROTOCOL(" p:");
  3066. SERIAL_PROTOCOL(Kp);
  3067. SERIAL_PROTOCOL(" i:");
  3068. SERIAL_PROTOCOL(unscalePID_i(Ki));
  3069. SERIAL_PROTOCOL(" d:");
  3070. SERIAL_PROTOCOL(unscalePID_d(Kd));
  3071. #ifdef PID_ADD_EXTRUSION_RATE
  3072. SERIAL_PROTOCOL(" c:");
  3073. //Kc does not have scaling applied above, or in resetting defaults
  3074. SERIAL_PROTOCOL(Kc);
  3075. #endif
  3076. SERIAL_PROTOCOLLN("");
  3077. }
  3078. break;
  3079. #endif //PIDTEMP
  3080. #ifdef PIDTEMPBED
  3081. case 304: // M304
  3082. {
  3083. if(code_seen('P')) bedKp = code_value();
  3084. if(code_seen('I')) bedKi = scalePID_i(code_value());
  3085. if(code_seen('D')) bedKd = scalePID_d(code_value());
  3086. updatePID();
  3087. SERIAL_PROTOCOL(MSG_OK);
  3088. SERIAL_PROTOCOL(" p:");
  3089. SERIAL_PROTOCOL(bedKp);
  3090. SERIAL_PROTOCOL(" i:");
  3091. SERIAL_PROTOCOL(unscalePID_i(bedKi));
  3092. SERIAL_PROTOCOL(" d:");
  3093. SERIAL_PROTOCOL(unscalePID_d(bedKd));
  3094. SERIAL_PROTOCOLLN("");
  3095. }
  3096. break;
  3097. #endif //PIDTEMP
  3098. case 240: // M240 Triggers a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/
  3099. {
  3100. #ifdef CHDK
  3101. SET_OUTPUT(CHDK);
  3102. WRITE(CHDK, HIGH);
  3103. chdkHigh = millis();
  3104. chdkActive = true;
  3105. #else
  3106. #if defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1
  3107. const uint8_t NUM_PULSES=16;
  3108. const float PULSE_LENGTH=0.01524;
  3109. for(int i=0; i < NUM_PULSES; i++) {
  3110. WRITE(PHOTOGRAPH_PIN, HIGH);
  3111. _delay_ms(PULSE_LENGTH);
  3112. WRITE(PHOTOGRAPH_PIN, LOW);
  3113. _delay_ms(PULSE_LENGTH);
  3114. }
  3115. delay(7.33);
  3116. for(int i=0; i < NUM_PULSES; i++) {
  3117. WRITE(PHOTOGRAPH_PIN, HIGH);
  3118. _delay_ms(PULSE_LENGTH);
  3119. WRITE(PHOTOGRAPH_PIN, LOW);
  3120. _delay_ms(PULSE_LENGTH);
  3121. }
  3122. #endif
  3123. #endif //chdk end if
  3124. }
  3125. break;
  3126. #ifdef DOGLCD
  3127. case 250: // M250 Set LCD contrast value: C<value> (value 0..63)
  3128. {
  3129. if (code_seen('C')) {
  3130. lcd_setcontrast( ((int)code_value())&63 );
  3131. }
  3132. SERIAL_PROTOCOLPGM("lcd contrast value: ");
  3133. SERIAL_PROTOCOL(lcd_contrast);
  3134. SERIAL_PROTOCOLLN("");
  3135. }
  3136. break;
  3137. #endif
  3138. #ifdef PREVENT_DANGEROUS_EXTRUDE
  3139. case 302: // allow cold extrudes, or set the minimum extrude temperature
  3140. {
  3141. float temp = .0;
  3142. if (code_seen('S')) temp=code_value();
  3143. set_extrude_min_temp(temp);
  3144. }
  3145. break;
  3146. #endif
  3147. case 303: // M303 PID autotune
  3148. {
  3149. float temp = 150.0;
  3150. int e=0;
  3151. int c=5;
  3152. if (code_seen('E')) e=code_value();
  3153. if (e<0)
  3154. temp=70;
  3155. if (code_seen('S')) temp=code_value();
  3156. if (code_seen('C')) c=code_value();
  3157. PID_autotune(temp, e, c);
  3158. }
  3159. break;
  3160. #ifdef SCARA
  3161. case 360: // M360 SCARA Theta pos1
  3162. SERIAL_ECHOLN(" Cal: Theta 0 ");
  3163. //SoftEndsEnabled = false; // Ignore soft endstops during calibration
  3164. //SERIAL_ECHOLN(" Soft endstops disabled ");
  3165. if(Stopped == false) {
  3166. //get_coordinates(); // For X Y Z E F
  3167. delta[X_AXIS] = 0;
  3168. delta[Y_AXIS] = 120;
  3169. calculate_SCARA_forward_Transform(delta);
  3170. destination[X_AXIS] = delta[X_AXIS]/axis_scaling[X_AXIS];
  3171. destination[Y_AXIS] = delta[Y_AXIS]/axis_scaling[Y_AXIS];
  3172. prepare_move();
  3173. //ClearToSend();
  3174. return;
  3175. }
  3176. break;
  3177. case 361: // SCARA Theta pos2
  3178. SERIAL_ECHOLN(" Cal: Theta 90 ");
  3179. //SoftEndsEnabled = false; // Ignore soft endstops during calibration
  3180. //SERIAL_ECHOLN(" Soft endstops disabled ");
  3181. if(Stopped == false) {
  3182. //get_coordinates(); // For X Y Z E F
  3183. delta[X_AXIS] = 90;
  3184. delta[Y_AXIS] = 130;
  3185. calculate_SCARA_forward_Transform(delta);
  3186. destination[X_AXIS] = delta[X_AXIS]/axis_scaling[X_AXIS];
  3187. destination[Y_AXIS] = delta[Y_AXIS]/axis_scaling[Y_AXIS];
  3188. prepare_move();
  3189. //ClearToSend();
  3190. return;
  3191. }
  3192. break;
  3193. case 362: // SCARA Psi pos1
  3194. SERIAL_ECHOLN(" Cal: Psi 0 ");
  3195. //SoftEndsEnabled = false; // Ignore soft endstops during calibration
  3196. //SERIAL_ECHOLN(" Soft endstops disabled ");
  3197. if(Stopped == false) {
  3198. //get_coordinates(); // For X Y Z E F
  3199. delta[X_AXIS] = 60;
  3200. delta[Y_AXIS] = 180;
  3201. calculate_SCARA_forward_Transform(delta);
  3202. destination[X_AXIS] = delta[X_AXIS]/axis_scaling[X_AXIS];
  3203. destination[Y_AXIS] = delta[Y_AXIS]/axis_scaling[Y_AXIS];
  3204. prepare_move();
  3205. //ClearToSend();
  3206. return;
  3207. }
  3208. break;
  3209. case 363: // SCARA Psi pos2
  3210. SERIAL_ECHOLN(" Cal: Psi 90 ");
  3211. //SoftEndsEnabled = false; // Ignore soft endstops during calibration
  3212. //SERIAL_ECHOLN(" Soft endstops disabled ");
  3213. if(Stopped == false) {
  3214. //get_coordinates(); // For X Y Z E F
  3215. delta[X_AXIS] = 50;
  3216. delta[Y_AXIS] = 90;
  3217. calculate_SCARA_forward_Transform(delta);
  3218. destination[X_AXIS] = delta[X_AXIS]/axis_scaling[X_AXIS];
  3219. destination[Y_AXIS] = delta[Y_AXIS]/axis_scaling[Y_AXIS];
  3220. prepare_move();
  3221. //ClearToSend();
  3222. return;
  3223. }
  3224. break;
  3225. case 364: // SCARA Psi pos3 (90 deg to Theta)
  3226. SERIAL_ECHOLN(" Cal: Theta-Psi 90 ");
  3227. // SoftEndsEnabled = false; // Ignore soft endstops during calibration
  3228. //SERIAL_ECHOLN(" Soft endstops disabled ");
  3229. if(Stopped == false) {
  3230. //get_coordinates(); // For X Y Z E F
  3231. delta[X_AXIS] = 45;
  3232. delta[Y_AXIS] = 135;
  3233. calculate_SCARA_forward_Transform(delta);
  3234. destination[X_AXIS] = delta[X_AXIS]/axis_scaling[X_AXIS];
  3235. destination[Y_AXIS] = delta[Y_AXIS]/axis_scaling[Y_AXIS];
  3236. prepare_move();
  3237. //ClearToSend();
  3238. return;
  3239. }
  3240. break;
  3241. case 365: // M364 Set SCARA scaling for X Y Z
  3242. for(int8_t i=0; i < 3; i++)
  3243. {
  3244. if(code_seen(axis_codes[i]))
  3245. {
  3246. axis_scaling[i] = code_value();
  3247. }
  3248. }
  3249. break;
  3250. #endif
  3251. case 400: // M400 finish all moves
  3252. {
  3253. st_synchronize();
  3254. }
  3255. break;
  3256. #if defined(ENABLE_AUTO_BED_LEVELING) && defined(SERVO_ENDSTOPS) && not defined(Z_PROBE_SLED)
  3257. case 401:
  3258. {
  3259. engage_z_probe(); // Engage Z Servo endstop if available
  3260. }
  3261. break;
  3262. case 402:
  3263. {
  3264. retract_z_probe(); // Retract Z Servo endstop if enabled
  3265. }
  3266. break;
  3267. #endif
  3268. #ifdef FILAMENT_SENSOR
  3269. case 404: //M404 Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or display nominal filament width
  3270. {
  3271. #if (FILWIDTH_PIN > -1)
  3272. if(code_seen('N')) filament_width_nominal=code_value();
  3273. else{
  3274. SERIAL_PROTOCOLPGM("Filament dia (nominal mm):");
  3275. SERIAL_PROTOCOLLN(filament_width_nominal);
  3276. }
  3277. #endif
  3278. }
  3279. break;
  3280. case 405: //M405 Turn on filament sensor for control
  3281. {
  3282. if(code_seen('D')) meas_delay_cm=code_value();
  3283. if(meas_delay_cm> MAX_MEASUREMENT_DELAY)
  3284. meas_delay_cm = MAX_MEASUREMENT_DELAY;
  3285. if(delay_index2 == -1) //initialize the ring buffer if it has not been done since startup
  3286. {
  3287. int temp_ratio = widthFil_to_size_ratio();
  3288. for (delay_index1=0; delay_index1<(MAX_MEASUREMENT_DELAY+1); ++delay_index1 ){
  3289. measurement_delay[delay_index1]=temp_ratio-100; //subtract 100 to scale within a signed byte
  3290. }
  3291. delay_index1=0;
  3292. delay_index2=0;
  3293. }
  3294. filament_sensor = true ;
  3295. //SERIAL_PROTOCOLPGM("Filament dia (measured mm):");
  3296. //SERIAL_PROTOCOL(filament_width_meas);
  3297. //SERIAL_PROTOCOLPGM("Extrusion ratio(%):");
  3298. //SERIAL_PROTOCOL(extrudemultiply);
  3299. }
  3300. break;
  3301. case 406: //M406 Turn off filament sensor for control
  3302. {
  3303. filament_sensor = false ;
  3304. }
  3305. break;
  3306. case 407: //M407 Display measured filament diameter
  3307. {
  3308. SERIAL_PROTOCOLPGM("Filament dia (measured mm):");
  3309. SERIAL_PROTOCOLLN(filament_width_meas);
  3310. }
  3311. break;
  3312. #endif
  3313. case 500: // M500 Store settings in EEPROM
  3314. {
  3315. Config_StoreSettings();
  3316. }
  3317. break;
  3318. case 501: // M501 Read settings from EEPROM
  3319. {
  3320. Config_RetrieveSettings();
  3321. }
  3322. break;
  3323. case 502: // M502 Revert to default settings
  3324. {
  3325. Config_ResetDefault();
  3326. }
  3327. break;
  3328. case 503: // M503 print settings currently in memory
  3329. {
  3330. Config_PrintSettings();
  3331. }
  3332. break;
  3333. case 509: //M509 Force language selection
  3334. {
  3335. lcd_force_language_selection();
  3336. SERIAL_ECHO_START;
  3337. SERIAL_PROTOCOLPGM(("LANG SEL FORCED"));
  3338. }
  3339. break;
  3340. #ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
  3341. case 540:
  3342. {
  3343. if(code_seen('S')) abort_on_endstop_hit = code_value() > 0;
  3344. }
  3345. break;
  3346. #endif
  3347. #ifdef CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
  3348. case CUSTOM_M_CODE_SET_Z_PROBE_OFFSET:
  3349. {
  3350. float value;
  3351. if (code_seen('Z'))
  3352. {
  3353. value = code_value();
  3354. if ((Z_PROBE_OFFSET_RANGE_MIN <= value) && (value <= Z_PROBE_OFFSET_RANGE_MAX))
  3355. {
  3356. zprobe_zoffset = -value; // compare w/ line 278 of ConfigurationStore.cpp
  3357. SERIAL_ECHO_START;
  3358. SERIAL_ECHOLNRPGM(CAT4(MSG_ZPROBE_ZOFFSET, " ", MSG_OK,PSTR("")));
  3359. SERIAL_PROTOCOLLN("");
  3360. }
  3361. else
  3362. {
  3363. SERIAL_ECHO_START;
  3364. SERIAL_ECHORPGM(MSG_ZPROBE_ZOFFSET);
  3365. SERIAL_ECHORPGM(MSG_Z_MIN);
  3366. SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MIN);
  3367. SERIAL_ECHORPGM(MSG_Z_MAX);
  3368. SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MAX);
  3369. SERIAL_PROTOCOLLN("");
  3370. }
  3371. }
  3372. else
  3373. {
  3374. SERIAL_ECHO_START;
  3375. SERIAL_ECHOLNRPGM(CAT2(MSG_ZPROBE_ZOFFSET, PSTR(" : ")));
  3376. SERIAL_ECHO(-zprobe_zoffset);
  3377. SERIAL_PROTOCOLLN("");
  3378. }
  3379. break;
  3380. }
  3381. #endif // CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
  3382. #ifdef FILAMENTCHANGEENABLE
  3383. case 600: //Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
  3384. {
  3385. feedmultiplyBckp=feedmultiply;
  3386. int8_t TooLowZ = 0;
  3387. float target[4];
  3388. float lastpos[4];
  3389. target[X_AXIS]=current_position[X_AXIS];
  3390. target[Y_AXIS]=current_position[Y_AXIS];
  3391. target[Z_AXIS]=current_position[Z_AXIS];
  3392. target[E_AXIS]=current_position[E_AXIS];
  3393. lastpos[X_AXIS]=current_position[X_AXIS];
  3394. lastpos[Y_AXIS]=current_position[Y_AXIS];
  3395. lastpos[Z_AXIS]=current_position[Z_AXIS];
  3396. lastpos[E_AXIS]=current_position[E_AXIS];
  3397. //Restract extruder
  3398. if(code_seen('E'))
  3399. {
  3400. target[E_AXIS]+= code_value();
  3401. }
  3402. else
  3403. {
  3404. #ifdef FILAMENTCHANGE_FIRSTRETRACT
  3405. target[E_AXIS]+= FILAMENTCHANGE_FIRSTRETRACT ;
  3406. #endif
  3407. }
  3408. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder);
  3409. //Lift Z
  3410. if(code_seen('Z'))
  3411. {
  3412. target[Z_AXIS]+= code_value();
  3413. }
  3414. else
  3415. {
  3416. #ifdef FILAMENTCHANGE_ZADD
  3417. target[Z_AXIS]+= FILAMENTCHANGE_ZADD ;
  3418. if(target[Z_AXIS] < 10){
  3419. target[Z_AXIS]+= 10 ;
  3420. TooLowZ = 1;
  3421. }else{
  3422. TooLowZ = 0;
  3423. }
  3424. #endif
  3425. }
  3426. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_ZFEED, active_extruder);
  3427. //Move XY to side
  3428. if(code_seen('X'))
  3429. {
  3430. target[X_AXIS]+= code_value();
  3431. }
  3432. else
  3433. {
  3434. #ifdef FILAMENTCHANGE_XPOS
  3435. target[X_AXIS]= FILAMENTCHANGE_XPOS ;
  3436. #endif
  3437. }
  3438. if(code_seen('Y'))
  3439. {
  3440. target[Y_AXIS]= code_value();
  3441. }
  3442. else
  3443. {
  3444. #ifdef FILAMENTCHANGE_YPOS
  3445. target[Y_AXIS]= FILAMENTCHANGE_YPOS ;
  3446. #endif
  3447. }
  3448. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_XYFEED, active_extruder);
  3449. // Unload filament
  3450. if(code_seen('L'))
  3451. {
  3452. target[E_AXIS]+= code_value();
  3453. }
  3454. else
  3455. {
  3456. #ifdef FILAMENTCHANGE_FINALRETRACT
  3457. target[E_AXIS]+= FILAMENTCHANGE_FINALRETRACT ;
  3458. #endif
  3459. }
  3460. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder);
  3461. //finish moves
  3462. st_synchronize();
  3463. //disable extruder steppers so filament can be removed
  3464. disable_e0();
  3465. disable_e1();
  3466. disable_e2();
  3467. delay(100);
  3468. //Wait for user to insert filament
  3469. uint8_t cnt=0;
  3470. int counterBeep = 0;
  3471. lcd_wait_interact();
  3472. while(!lcd_clicked()){
  3473. cnt++;
  3474. manage_heater();
  3475. manage_inactivity(true);
  3476. if(cnt==0)
  3477. {
  3478. #if BEEPER > 0
  3479. if (counterBeep== 500){
  3480. counterBeep = 0;
  3481. }
  3482. SET_OUTPUT(BEEPER);
  3483. if (counterBeep== 0){
  3484. WRITE(BEEPER,HIGH);
  3485. }
  3486. if (counterBeep== 20){
  3487. WRITE(BEEPER,LOW);
  3488. }
  3489. counterBeep++;
  3490. #else
  3491. #if !defined(LCD_FEEDBACK_FREQUENCY_HZ) || !defined(LCD_FEEDBACK_FREQUENCY_DURATION_MS)
  3492. lcd_buzz(1000/6,100);
  3493. #else
  3494. lcd_buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS,LCD_FEEDBACK_FREQUENCY_HZ);
  3495. #endif
  3496. #endif
  3497. }
  3498. }
  3499. //Filament inserted
  3500. WRITE(BEEPER,LOW);
  3501. //Feed the filament to the end of nozzle quickly
  3502. target[E_AXIS]+= FILAMENTCHANGE_FIRSTFEED ;
  3503. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EFEED, active_extruder);
  3504. //Extrude some filament
  3505. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  3506. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EXFEED, active_extruder);
  3507. //Wait for user to check the state
  3508. lcd_change_fil_state = 0;
  3509. lcd_loading_filament();
  3510. while ((lcd_change_fil_state == 0)||(lcd_change_fil_state != 1)){
  3511. lcd_change_fil_state = 0;
  3512. lcd_alright();
  3513. switch(lcd_change_fil_state){
  3514. // Filament failed to load so load it again
  3515. case 2:
  3516. target[E_AXIS]+= FILAMENTCHANGE_FIRSTFEED ;
  3517. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EFEED, active_extruder);
  3518. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  3519. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EXFEED, active_extruder);
  3520. lcd_loading_filament();
  3521. break;
  3522. // Filament loaded properly but color is not clear
  3523. case 3:
  3524. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  3525. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  3526. lcd_loading_color();
  3527. break;
  3528. // Everything good
  3529. default:
  3530. lcd_change_success();
  3531. break;
  3532. }
  3533. }
  3534. //Not let's go back to print
  3535. //Feed a little of filament to stabilize pressure
  3536. target[E_AXIS]+= FILAMENTCHANGE_RECFEED;
  3537. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EXFEED, active_extruder);
  3538. //Retract
  3539. target[E_AXIS]+= FILAMENTCHANGE_FIRSTRETRACT;
  3540. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder);
  3541. //plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 70, active_extruder); //should do nothing
  3542. //Move XY back
  3543. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_XYFEED, active_extruder);
  3544. //Move Z back
  3545. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_ZFEED, active_extruder);
  3546. target[E_AXIS]= target[E_AXIS] - FILAMENTCHANGE_FIRSTRETRACT;
  3547. //Unretract
  3548. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder);
  3549. //Set E position to original
  3550. plan_set_e_position(lastpos[E_AXIS]);
  3551. //Recover feed rate
  3552. feedmultiply=feedmultiplyBckp;
  3553. char cmd[9];
  3554. sprintf_P(cmd, PSTR("M220 S%i"), feedmultiplyBckp);
  3555. enquecommand(cmd);
  3556. }
  3557. break;
  3558. #endif //FILAMENTCHANGEENABLE
  3559. #ifdef DUAL_X_CARRIAGE
  3560. case 605: // Set dual x-carriage movement mode:
  3561. // M605 S0: Full control mode. The slicer has full control over x-carriage movement
  3562. // M605 S1: Auto-park mode. The inactive head will auto park/unpark without slicer involvement
  3563. // M605 S2 [Xnnn] [Rmmm]: Duplication mode. The second extruder will duplicate the first with nnn
  3564. // millimeters x-offset and an optional differential hotend temperature of
  3565. // mmm degrees. E.g., with "M605 S2 X100 R2" the second extruder will duplicate
  3566. // the first with a spacing of 100mm in the x direction and 2 degrees hotter.
  3567. //
  3568. // Note: the X axis should be homed after changing dual x-carriage mode.
  3569. {
  3570. st_synchronize();
  3571. if (code_seen('S'))
  3572. dual_x_carriage_mode = code_value();
  3573. if (dual_x_carriage_mode == DXC_DUPLICATION_MODE)
  3574. {
  3575. if (code_seen('X'))
  3576. duplicate_extruder_x_offset = max(code_value(),X2_MIN_POS - x_home_pos(0));
  3577. if (code_seen('R'))
  3578. duplicate_extruder_temp_offset = code_value();
  3579. SERIAL_ECHO_START;
  3580. SERIAL_ECHORPGM(MSG_HOTEND_OFFSET);
  3581. SERIAL_ECHO(" ");
  3582. SERIAL_ECHO(extruder_offset[X_AXIS][0]);
  3583. SERIAL_ECHO(",");
  3584. SERIAL_ECHO(extruder_offset[Y_AXIS][0]);
  3585. SERIAL_ECHO(" ");
  3586. SERIAL_ECHO(duplicate_extruder_x_offset);
  3587. SERIAL_ECHO(",");
  3588. SERIAL_ECHOLN(extruder_offset[Y_AXIS][1]);
  3589. }
  3590. else if (dual_x_carriage_mode != DXC_FULL_CONTROL_MODE && dual_x_carriage_mode != DXC_AUTO_PARK_MODE)
  3591. {
  3592. dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
  3593. }
  3594. active_extruder_parked = false;
  3595. extruder_duplication_enabled = false;
  3596. delayed_move_time = 0;
  3597. }
  3598. break;
  3599. #endif //DUAL_X_CARRIAGE
  3600. case 907: // M907 Set digital trimpot motor current using axis codes.
  3601. {
  3602. #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
  3603. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) digipot_current(i,code_value());
  3604. if(code_seen('B')) digipot_current(4,code_value());
  3605. if(code_seen('S')) for(int i=0;i<=4;i++) digipot_current(i,code_value());
  3606. #endif
  3607. #ifdef MOTOR_CURRENT_PWM_XY_PIN
  3608. if(code_seen('X')) digipot_current(0, code_value());
  3609. #endif
  3610. #ifdef MOTOR_CURRENT_PWM_Z_PIN
  3611. if(code_seen('Z')) digipot_current(1, code_value());
  3612. #endif
  3613. #ifdef MOTOR_CURRENT_PWM_E_PIN
  3614. if(code_seen('E')) digipot_current(2, code_value());
  3615. #endif
  3616. #ifdef DIGIPOT_I2C
  3617. // this one uses actual amps in floating point
  3618. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) digipot_i2c_set_current(i, code_value());
  3619. // for each additional extruder (named B,C,D,E..., channels 4,5,6,7...)
  3620. for(int i=NUM_AXIS;i<DIGIPOT_I2C_NUM_CHANNELS;i++) if(code_seen('B'+i-NUM_AXIS)) digipot_i2c_set_current(i, code_value());
  3621. #endif
  3622. }
  3623. break;
  3624. case 908: // M908 Control digital trimpot directly.
  3625. {
  3626. #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
  3627. uint8_t channel,current;
  3628. if(code_seen('P')) channel=code_value();
  3629. if(code_seen('S')) current=code_value();
  3630. digitalPotWrite(channel, current);
  3631. #endif
  3632. }
  3633. break;
  3634. case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
  3635. {
  3636. #if defined(X_MS1_PIN) && X_MS1_PIN > -1
  3637. if(code_seen('S')) for(int i=0;i<=4;i++) microstep_mode(i,code_value());
  3638. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_mode(i,(uint8_t)code_value());
  3639. if(code_seen('B')) microstep_mode(4,code_value());
  3640. microstep_readings();
  3641. #endif
  3642. }
  3643. break;
  3644. case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low.
  3645. {
  3646. #if defined(X_MS1_PIN) && X_MS1_PIN > -1
  3647. if(code_seen('S')) switch((int)code_value())
  3648. {
  3649. case 1:
  3650. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_ms(i,code_value(),-1);
  3651. if(code_seen('B')) microstep_ms(4,code_value(),-1);
  3652. break;
  3653. case 2:
  3654. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_ms(i,-1,code_value());
  3655. if(code_seen('B')) microstep_ms(4,-1,code_value());
  3656. break;
  3657. }
  3658. microstep_readings();
  3659. #endif
  3660. }
  3661. break;
  3662. case 999: // M999: Restart after being stopped
  3663. Stopped = false;
  3664. lcd_reset_alert_level();
  3665. gcode_LastN = Stopped_gcode_LastN;
  3666. FlushSerialRequestResend();
  3667. break;
  3668. }
  3669. }
  3670. else if(code_seen('T'))
  3671. {
  3672. tmp_extruder = code_value();
  3673. if(tmp_extruder >= EXTRUDERS) {
  3674. SERIAL_ECHO_START;
  3675. SERIAL_ECHO("T");
  3676. SERIAL_ECHO(tmp_extruder);
  3677. SERIAL_ECHOLN(MSG_INVALID_EXTRUDER);
  3678. }
  3679. else {
  3680. boolean make_move = false;
  3681. if(code_seen('F')) {
  3682. make_move = true;
  3683. next_feedrate = code_value();
  3684. if(next_feedrate > 0.0) {
  3685. feedrate = next_feedrate;
  3686. }
  3687. }
  3688. #if EXTRUDERS > 1
  3689. if(tmp_extruder != active_extruder) {
  3690. // Save current position to return to after applying extruder offset
  3691. memcpy(destination, current_position, sizeof(destination));
  3692. #ifdef DUAL_X_CARRIAGE
  3693. if (dual_x_carriage_mode == DXC_AUTO_PARK_MODE && Stopped == false &&
  3694. (delayed_move_time != 0 || current_position[X_AXIS] != x_home_pos(active_extruder)))
  3695. {
  3696. // Park old head: 1) raise 2) move to park position 3) lower
  3697. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] + TOOLCHANGE_PARK_ZLIFT,
  3698. current_position[E_AXIS], max_feedrate[Z_AXIS], active_extruder);
  3699. plan_buffer_line(x_home_pos(active_extruder), current_position[Y_AXIS], current_position[Z_AXIS] + TOOLCHANGE_PARK_ZLIFT,
  3700. current_position[E_AXIS], max_feedrate[X_AXIS], active_extruder);
  3701. plan_buffer_line(x_home_pos(active_extruder), current_position[Y_AXIS], current_position[Z_AXIS],
  3702. current_position[E_AXIS], max_feedrate[Z_AXIS], active_extruder);
  3703. st_synchronize();
  3704. }
  3705. // apply Y & Z extruder offset (x offset is already used in determining home pos)
  3706. current_position[Y_AXIS] = current_position[Y_AXIS] -
  3707. extruder_offset[Y_AXIS][active_extruder] +
  3708. extruder_offset[Y_AXIS][tmp_extruder];
  3709. current_position[Z_AXIS] = current_position[Z_AXIS] -
  3710. extruder_offset[Z_AXIS][active_extruder] +
  3711. extruder_offset[Z_AXIS][tmp_extruder];
  3712. active_extruder = tmp_extruder;
  3713. // This function resets the max/min values - the current position may be overwritten below.
  3714. axis_is_at_home(X_AXIS);
  3715. if (dual_x_carriage_mode == DXC_FULL_CONTROL_MODE)
  3716. {
  3717. current_position[X_AXIS] = inactive_extruder_x_pos;
  3718. inactive_extruder_x_pos = destination[X_AXIS];
  3719. }
  3720. else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE)
  3721. {
  3722. active_extruder_parked = (active_extruder == 0); // this triggers the second extruder to move into the duplication position
  3723. if (active_extruder == 0 || active_extruder_parked)
  3724. current_position[X_AXIS] = inactive_extruder_x_pos;
  3725. else
  3726. current_position[X_AXIS] = destination[X_AXIS] + duplicate_extruder_x_offset;
  3727. inactive_extruder_x_pos = destination[X_AXIS];
  3728. extruder_duplication_enabled = false;
  3729. }
  3730. else
  3731. {
  3732. // record raised toolhead position for use by unpark
  3733. memcpy(raised_parked_position, current_position, sizeof(raised_parked_position));
  3734. raised_parked_position[Z_AXIS] += TOOLCHANGE_UNPARK_ZLIFT;
  3735. active_extruder_parked = true;
  3736. delayed_move_time = 0;
  3737. }
  3738. #else
  3739. // Offset extruder (only by XY)
  3740. int i;
  3741. for(i = 0; i < 2; i++) {
  3742. current_position[i] = current_position[i] -
  3743. extruder_offset[i][active_extruder] +
  3744. extruder_offset[i][tmp_extruder];
  3745. }
  3746. // Set the new active extruder and position
  3747. active_extruder = tmp_extruder;
  3748. #endif //else DUAL_X_CARRIAGE
  3749. #ifdef DELTA
  3750. calculate_delta(current_position); // change cartesian kinematic to delta kinematic;
  3751. //sent position to plan_set_position();
  3752. plan_set_position(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS],current_position[E_AXIS]);
  3753. #else
  3754. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  3755. #endif
  3756. // Move to the old position if 'F' was in the parameters
  3757. if(make_move && Stopped == false) {
  3758. prepare_move();
  3759. }
  3760. }
  3761. #endif
  3762. SERIAL_ECHO_START;
  3763. SERIAL_ECHO(MSG_ACTIVE_EXTRUDER);
  3764. SERIAL_PROTOCOLLN((int)active_extruder);
  3765. }
  3766. }
  3767. else
  3768. {
  3769. SERIAL_ECHO_START;
  3770. SERIAL_ECHORPGM(MSG_UNKNOWN_COMMAND);
  3771. SERIAL_ECHO(cmdbuffer[bufindr]);
  3772. SERIAL_ECHOLNPGM("\"");
  3773. }
  3774. ClearToSend();
  3775. }
  3776. void FlushSerialRequestResend()
  3777. {
  3778. //char cmdbuffer[bufindr][100]="Resend:";
  3779. MYSERIAL.flush();
  3780. SERIAL_PROTOCOLRPGM(MSG_RESEND);
  3781. SERIAL_PROTOCOLLN(gcode_LastN + 1);
  3782. ClearToSend();
  3783. }
  3784. void ClearToSend()
  3785. {
  3786. previous_millis_cmd = millis();
  3787. #ifdef SDSUPPORT
  3788. if(fromsd[bufindr])
  3789. return;
  3790. #endif //SDSUPPORT
  3791. SERIAL_PROTOCOLLNRPGM(MSG_OK);
  3792. }
  3793. void get_coordinates()
  3794. {
  3795. bool seen[4]={false,false,false,false};
  3796. for(int8_t i=0; i < NUM_AXIS; i++) {
  3797. if(code_seen(axis_codes[i]))
  3798. {
  3799. destination[i] = (float)code_value() + (axis_relative_modes[i] || relative_mode)*current_position[i];
  3800. seen[i]=true;
  3801. }
  3802. else destination[i] = current_position[i]; //Are these else lines really needed?
  3803. }
  3804. if(code_seen('F')) {
  3805. next_feedrate = code_value();
  3806. if(next_feedrate > 0.0) feedrate = next_feedrate;
  3807. }
  3808. }
  3809. void get_arc_coordinates()
  3810. {
  3811. #ifdef SF_ARC_FIX
  3812. bool relative_mode_backup = relative_mode;
  3813. relative_mode = true;
  3814. #endif
  3815. get_coordinates();
  3816. #ifdef SF_ARC_FIX
  3817. relative_mode=relative_mode_backup;
  3818. #endif
  3819. if(code_seen('I')) {
  3820. offset[0] = code_value();
  3821. }
  3822. else {
  3823. offset[0] = 0.0;
  3824. }
  3825. if(code_seen('J')) {
  3826. offset[1] = code_value();
  3827. }
  3828. else {
  3829. offset[1] = 0.0;
  3830. }
  3831. }
  3832. void clamp_to_software_endstops(float target[3])
  3833. {
  3834. if (min_software_endstops) {
  3835. if (target[X_AXIS] < min_pos[X_AXIS]) target[X_AXIS] = min_pos[X_AXIS];
  3836. if (target[Y_AXIS] < min_pos[Y_AXIS]) target[Y_AXIS] = min_pos[Y_AXIS];
  3837. float negative_z_offset = 0;
  3838. #ifdef ENABLE_AUTO_BED_LEVELING
  3839. if (Z_PROBE_OFFSET_FROM_EXTRUDER < 0) negative_z_offset = negative_z_offset + Z_PROBE_OFFSET_FROM_EXTRUDER;
  3840. if (add_homing[Z_AXIS] < 0) negative_z_offset = negative_z_offset + add_homing[Z_AXIS];
  3841. #endif
  3842. if (target[Z_AXIS] < min_pos[Z_AXIS]+negative_z_offset) target[Z_AXIS] = min_pos[Z_AXIS]+negative_z_offset;
  3843. }
  3844. if (max_software_endstops) {
  3845. if (target[X_AXIS] > max_pos[X_AXIS]) target[X_AXIS] = max_pos[X_AXIS];
  3846. if (target[Y_AXIS] > max_pos[Y_AXIS]) target[Y_AXIS] = max_pos[Y_AXIS];
  3847. if (target[Z_AXIS] > max_pos[Z_AXIS]) target[Z_AXIS] = max_pos[Z_AXIS];
  3848. }
  3849. }
  3850. #ifdef DELTA
  3851. void recalc_delta_settings(float radius, float diagonal_rod)
  3852. {
  3853. delta_tower1_x= -SIN_60*radius; // front left tower
  3854. delta_tower1_y= -COS_60*radius;
  3855. delta_tower2_x= SIN_60*radius; // front right tower
  3856. delta_tower2_y= -COS_60*radius;
  3857. delta_tower3_x= 0.0; // back middle tower
  3858. delta_tower3_y= radius;
  3859. delta_diagonal_rod_2= sq(diagonal_rod);
  3860. }
  3861. void calculate_delta(float cartesian[3])
  3862. {
  3863. delta[X_AXIS] = sqrt(delta_diagonal_rod_2
  3864. - sq(delta_tower1_x-cartesian[X_AXIS])
  3865. - sq(delta_tower1_y-cartesian[Y_AXIS])
  3866. ) + cartesian[Z_AXIS];
  3867. delta[Y_AXIS] = sqrt(delta_diagonal_rod_2
  3868. - sq(delta_tower2_x-cartesian[X_AXIS])
  3869. - sq(delta_tower2_y-cartesian[Y_AXIS])
  3870. ) + cartesian[Z_AXIS];
  3871. delta[Z_AXIS] = sqrt(delta_diagonal_rod_2
  3872. - sq(delta_tower3_x-cartesian[X_AXIS])
  3873. - sq(delta_tower3_y-cartesian[Y_AXIS])
  3874. ) + cartesian[Z_AXIS];
  3875. /*
  3876. SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]);
  3877. SERIAL_ECHOPGM(" y="); SERIAL_ECHO(cartesian[Y_AXIS]);
  3878. SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(cartesian[Z_AXIS]);
  3879. SERIAL_ECHOPGM("delta x="); SERIAL_ECHO(delta[X_AXIS]);
  3880. SERIAL_ECHOPGM(" y="); SERIAL_ECHO(delta[Y_AXIS]);
  3881. SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(delta[Z_AXIS]);
  3882. */
  3883. }
  3884. #endif
  3885. void prepare_move()
  3886. {
  3887. clamp_to_software_endstops(destination);
  3888. previous_millis_cmd = millis();
  3889. #ifdef SCARA //for now same as delta-code
  3890. float difference[NUM_AXIS];
  3891. for (int8_t i=0; i < NUM_AXIS; i++) {
  3892. difference[i] = destination[i] - current_position[i];
  3893. }
  3894. float cartesian_mm = sqrt( sq(difference[X_AXIS]) +
  3895. sq(difference[Y_AXIS]) +
  3896. sq(difference[Z_AXIS]));
  3897. if (cartesian_mm < 0.000001) { cartesian_mm = abs(difference[E_AXIS]); }
  3898. if (cartesian_mm < 0.000001) { return; }
  3899. float seconds = 6000 * cartesian_mm / feedrate / feedmultiply;
  3900. int steps = max(1, int(scara_segments_per_second * seconds));
  3901. //SERIAL_ECHOPGM("mm="); SERIAL_ECHO(cartesian_mm);
  3902. //SERIAL_ECHOPGM(" seconds="); SERIAL_ECHO(seconds);
  3903. //SERIAL_ECHOPGM(" steps="); SERIAL_ECHOLN(steps);
  3904. for (int s = 1; s <= steps; s++) {
  3905. float fraction = float(s) / float(steps);
  3906. for(int8_t i=0; i < NUM_AXIS; i++) {
  3907. destination[i] = current_position[i] + difference[i] * fraction;
  3908. }
  3909. calculate_delta(destination);
  3910. //SERIAL_ECHOPGM("destination[X_AXIS]="); SERIAL_ECHOLN(destination[X_AXIS]);
  3911. //SERIAL_ECHOPGM("destination[Y_AXIS]="); SERIAL_ECHOLN(destination[Y_AXIS]);
  3912. //SERIAL_ECHOPGM("destination[Z_AXIS]="); SERIAL_ECHOLN(destination[Z_AXIS]);
  3913. //SERIAL_ECHOPGM("delta[X_AXIS]="); SERIAL_ECHOLN(delta[X_AXIS]);
  3914. //SERIAL_ECHOPGM("delta[Y_AXIS]="); SERIAL_ECHOLN(delta[Y_AXIS]);
  3915. //SERIAL_ECHOPGM("delta[Z_AXIS]="); SERIAL_ECHOLN(delta[Z_AXIS]);
  3916. plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS],
  3917. destination[E_AXIS], feedrate*feedmultiply/60/100.0,
  3918. active_extruder);
  3919. }
  3920. #endif // SCARA
  3921. #ifdef DELTA
  3922. float difference[NUM_AXIS];
  3923. for (int8_t i=0; i < NUM_AXIS; i++) {
  3924. difference[i] = destination[i] - current_position[i];
  3925. }
  3926. float cartesian_mm = sqrt(sq(difference[X_AXIS]) +
  3927. sq(difference[Y_AXIS]) +
  3928. sq(difference[Z_AXIS]));
  3929. if (cartesian_mm < 0.000001) { cartesian_mm = abs(difference[E_AXIS]); }
  3930. if (cartesian_mm < 0.000001) { return; }
  3931. float seconds = 6000 * cartesian_mm / feedrate / feedmultiply;
  3932. int steps = max(1, int(delta_segments_per_second * seconds));
  3933. // SERIAL_ECHOPGM("mm="); SERIAL_ECHO(cartesian_mm);
  3934. // SERIAL_ECHOPGM(" seconds="); SERIAL_ECHO(seconds);
  3935. // SERIAL_ECHOPGM(" steps="); SERIAL_ECHOLN(steps);
  3936. for (int s = 1; s <= steps; s++) {
  3937. float fraction = float(s) / float(steps);
  3938. for(int8_t i=0; i < NUM_AXIS; i++) {
  3939. destination[i] = current_position[i] + difference[i] * fraction;
  3940. }
  3941. calculate_delta(destination);
  3942. plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS],
  3943. destination[E_AXIS], feedrate*feedmultiply/60/100.0,
  3944. active_extruder);
  3945. }
  3946. #endif // DELTA
  3947. #ifdef DUAL_X_CARRIAGE
  3948. if (active_extruder_parked)
  3949. {
  3950. if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && active_extruder == 0)
  3951. {
  3952. // move duplicate extruder into correct duplication position.
  3953. plan_set_position(inactive_extruder_x_pos, current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  3954. plan_buffer_line(current_position[X_AXIS] + duplicate_extruder_x_offset, current_position[Y_AXIS], current_position[Z_AXIS],
  3955. current_position[E_AXIS], max_feedrate[X_AXIS], 1);
  3956. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  3957. st_synchronize();
  3958. extruder_duplication_enabled = true;
  3959. active_extruder_parked = false;
  3960. }
  3961. else if (dual_x_carriage_mode == DXC_AUTO_PARK_MODE) // handle unparking of head
  3962. {
  3963. if (current_position[E_AXIS] == destination[E_AXIS])
  3964. {
  3965. // this is a travel move - skit it but keep track of current position (so that it can later
  3966. // be used as start of first non-travel move)
  3967. if (delayed_move_time != 0xFFFFFFFFUL)
  3968. {
  3969. memcpy(current_position, destination, sizeof(current_position));
  3970. if (destination[Z_AXIS] > raised_parked_position[Z_AXIS])
  3971. raised_parked_position[Z_AXIS] = destination[Z_AXIS];
  3972. delayed_move_time = millis();
  3973. return;
  3974. }
  3975. }
  3976. delayed_move_time = 0;
  3977. // unpark extruder: 1) raise, 2) move into starting XY position, 3) lower
  3978. plan_buffer_line(raised_parked_position[X_AXIS], raised_parked_position[Y_AXIS], raised_parked_position[Z_AXIS], current_position[E_AXIS], max_feedrate[Z_AXIS], active_extruder);
  3979. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], raised_parked_position[Z_AXIS],
  3980. current_position[E_AXIS], min(max_feedrate[X_AXIS],max_feedrate[Y_AXIS]), active_extruder);
  3981. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS],
  3982. current_position[E_AXIS], max_feedrate[Z_AXIS], active_extruder);
  3983. active_extruder_parked = false;
  3984. }
  3985. }
  3986. #endif //DUAL_X_CARRIAGE
  3987. #if ! (defined DELTA || defined SCARA)
  3988. // Do not use feedmultiply for E or Z only moves
  3989. if( (current_position[X_AXIS] == destination [X_AXIS]) && (current_position[Y_AXIS] == destination [Y_AXIS])) {
  3990. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  3991. }
  3992. else {
  3993. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply/60/100.0, active_extruder);
  3994. }
  3995. #endif // !(DELTA || SCARA)
  3996. for(int8_t i=0; i < NUM_AXIS; i++) {
  3997. current_position[i] = destination[i];
  3998. }
  3999. }
  4000. void prepare_arc_move(char isclockwise) {
  4001. float r = hypot(offset[X_AXIS], offset[Y_AXIS]); // Compute arc radius for mc_arc
  4002. // Trace the arc
  4003. mc_arc(current_position, destination, offset, X_AXIS, Y_AXIS, Z_AXIS, feedrate*feedmultiply/60/100.0, r, isclockwise, active_extruder);
  4004. // As far as the parser is concerned, the position is now == target. In reality the
  4005. // motion control system might still be processing the action and the real tool position
  4006. // in any intermediate location.
  4007. for(int8_t i=0; i < NUM_AXIS; i++) {
  4008. current_position[i] = destination[i];
  4009. }
  4010. previous_millis_cmd = millis();
  4011. }
  4012. #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
  4013. #if defined(FAN_PIN)
  4014. #if CONTROLLERFAN_PIN == FAN_PIN
  4015. #error "You cannot set CONTROLLERFAN_PIN equal to FAN_PIN"
  4016. #endif
  4017. #endif
  4018. unsigned long lastMotor = 0; //Save the time for when a motor was turned on last
  4019. unsigned long lastMotorCheck = 0;
  4020. void controllerFan()
  4021. {
  4022. if ((millis() - lastMotorCheck) >= 2500) //Not a time critical function, so we only check every 2500ms
  4023. {
  4024. lastMotorCheck = millis();
  4025. if(!READ(X_ENABLE_PIN) || !READ(Y_ENABLE_PIN) || !READ(Z_ENABLE_PIN) || (soft_pwm_bed > 0)
  4026. #if EXTRUDERS > 2
  4027. || !READ(E2_ENABLE_PIN)
  4028. #endif
  4029. #if EXTRUDER > 1
  4030. #if defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1
  4031. || !READ(X2_ENABLE_PIN)
  4032. #endif
  4033. || !READ(E1_ENABLE_PIN)
  4034. #endif
  4035. || !READ(E0_ENABLE_PIN)) //If any of the drivers are enabled...
  4036. {
  4037. lastMotor = millis(); //... set time to NOW so the fan will turn on
  4038. }
  4039. if ((millis() - lastMotor) >= (CONTROLLERFAN_SECS*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC...
  4040. {
  4041. digitalWrite(CONTROLLERFAN_PIN, 0);
  4042. analogWrite(CONTROLLERFAN_PIN, 0);
  4043. }
  4044. else
  4045. {
  4046. // allows digital or PWM fan output to be used (see M42 handling)
  4047. digitalWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
  4048. analogWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
  4049. }
  4050. }
  4051. }
  4052. #endif
  4053. #ifdef SCARA
  4054. void calculate_SCARA_forward_Transform(float f_scara[3])
  4055. {
  4056. // Perform forward kinematics, and place results in delta[3]
  4057. // The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014
  4058. float x_sin, x_cos, y_sin, y_cos;
  4059. //SERIAL_ECHOPGM("f_delta x="); SERIAL_ECHO(f_scara[X_AXIS]);
  4060. //SERIAL_ECHOPGM(" y="); SERIAL_ECHO(f_scara[Y_AXIS]);
  4061. x_sin = sin(f_scara[X_AXIS]/SCARA_RAD2DEG) * Linkage_1;
  4062. x_cos = cos(f_scara[X_AXIS]/SCARA_RAD2DEG) * Linkage_1;
  4063. y_sin = sin(f_scara[Y_AXIS]/SCARA_RAD2DEG) * Linkage_2;
  4064. y_cos = cos(f_scara[Y_AXIS]/SCARA_RAD2DEG) * Linkage_2;
  4065. // SERIAL_ECHOPGM(" x_sin="); SERIAL_ECHO(x_sin);
  4066. // SERIAL_ECHOPGM(" x_cos="); SERIAL_ECHO(x_cos);
  4067. // SERIAL_ECHOPGM(" y_sin="); SERIAL_ECHO(y_sin);
  4068. // SERIAL_ECHOPGM(" y_cos="); SERIAL_ECHOLN(y_cos);
  4069. delta[X_AXIS] = x_cos + y_cos + SCARA_offset_x; //theta
  4070. delta[Y_AXIS] = x_sin + y_sin + SCARA_offset_y; //theta+phi
  4071. //SERIAL_ECHOPGM(" delta[X_AXIS]="); SERIAL_ECHO(delta[X_AXIS]);
  4072. //SERIAL_ECHOPGM(" delta[Y_AXIS]="); SERIAL_ECHOLN(delta[Y_AXIS]);
  4073. }
  4074. void calculate_delta(float cartesian[3]){
  4075. //reverse kinematics.
  4076. // Perform reversed kinematics, and place results in delta[3]
  4077. // The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014
  4078. float SCARA_pos[2];
  4079. static float SCARA_C2, SCARA_S2, SCARA_K1, SCARA_K2, SCARA_theta, SCARA_psi;
  4080. SCARA_pos[X_AXIS] = cartesian[X_AXIS] * axis_scaling[X_AXIS] - SCARA_offset_x; //Translate SCARA to standard X Y
  4081. SCARA_pos[Y_AXIS] = cartesian[Y_AXIS] * axis_scaling[Y_AXIS] - SCARA_offset_y; // With scaling factor.
  4082. #if (Linkage_1 == Linkage_2)
  4083. SCARA_C2 = ( ( sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS]) ) / (2 * (float)L1_2) ) - 1;
  4084. #else
  4085. SCARA_C2 = ( sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS]) - (float)L1_2 - (float)L2_2 ) / 45000;
  4086. #endif
  4087. SCARA_S2 = sqrt( 1 - sq(SCARA_C2) );
  4088. SCARA_K1 = Linkage_1 + Linkage_2 * SCARA_C2;
  4089. SCARA_K2 = Linkage_2 * SCARA_S2;
  4090. SCARA_theta = ( atan2(SCARA_pos[X_AXIS],SCARA_pos[Y_AXIS])-atan2(SCARA_K1, SCARA_K2) ) * -1;
  4091. SCARA_psi = atan2(SCARA_S2,SCARA_C2);
  4092. delta[X_AXIS] = SCARA_theta * SCARA_RAD2DEG; // Multiply by 180/Pi - theta is support arm angle
  4093. delta[Y_AXIS] = (SCARA_theta + SCARA_psi) * SCARA_RAD2DEG; // - equal to sub arm angle (inverted motor)
  4094. delta[Z_AXIS] = cartesian[Z_AXIS];
  4095. /*
  4096. SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]);
  4097. SERIAL_ECHOPGM(" y="); SERIAL_ECHO(cartesian[Y_AXIS]);
  4098. SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(cartesian[Z_AXIS]);
  4099. SERIAL_ECHOPGM("scara x="); SERIAL_ECHO(SCARA_pos[X_AXIS]);
  4100. SERIAL_ECHOPGM(" y="); SERIAL_ECHOLN(SCARA_pos[Y_AXIS]);
  4101. SERIAL_ECHOPGM("delta x="); SERIAL_ECHO(delta[X_AXIS]);
  4102. SERIAL_ECHOPGM(" y="); SERIAL_ECHO(delta[Y_AXIS]);
  4103. SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(delta[Z_AXIS]);
  4104. SERIAL_ECHOPGM("C2="); SERIAL_ECHO(SCARA_C2);
  4105. SERIAL_ECHOPGM(" S2="); SERIAL_ECHO(SCARA_S2);
  4106. SERIAL_ECHOPGM(" Theta="); SERIAL_ECHO(SCARA_theta);
  4107. SERIAL_ECHOPGM(" Psi="); SERIAL_ECHOLN(SCARA_psi);
  4108. SERIAL_ECHOLN(" ");*/
  4109. }
  4110. #endif
  4111. #ifdef TEMP_STAT_LEDS
  4112. static bool blue_led = false;
  4113. static bool red_led = false;
  4114. static uint32_t stat_update = 0;
  4115. void handle_status_leds(void) {
  4116. float max_temp = 0.0;
  4117. if(millis() > stat_update) {
  4118. stat_update += 500; // Update every 0.5s
  4119. for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
  4120. max_temp = max(max_temp, degHotend(cur_extruder));
  4121. max_temp = max(max_temp, degTargetHotend(cur_extruder));
  4122. }
  4123. #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
  4124. max_temp = max(max_temp, degTargetBed());
  4125. max_temp = max(max_temp, degBed());
  4126. #endif
  4127. if((max_temp > 55.0) && (red_led == false)) {
  4128. digitalWrite(STAT_LED_RED, 1);
  4129. digitalWrite(STAT_LED_BLUE, 0);
  4130. red_led = true;
  4131. blue_led = false;
  4132. }
  4133. if((max_temp < 54.0) && (blue_led == false)) {
  4134. digitalWrite(STAT_LED_RED, 0);
  4135. digitalWrite(STAT_LED_BLUE, 1);
  4136. red_led = false;
  4137. blue_led = true;
  4138. }
  4139. }
  4140. }
  4141. #endif
  4142. void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument set in Marlin.h
  4143. {
  4144. #if defined(KILL_PIN) && KILL_PIN > -1
  4145. static int killCount = 0; // make the inactivity button a bit less responsive
  4146. const int KILL_DELAY = 10000;
  4147. #endif
  4148. #if defined(HOME_PIN) && HOME_PIN > -1
  4149. static int homeDebounceCount = 0; // poor man's debouncing count
  4150. const int HOME_DEBOUNCE_DELAY = 10000;
  4151. #endif
  4152. if(buflen < (BUFSIZE-1))
  4153. get_command();
  4154. if( (millis() - previous_millis_cmd) > max_inactive_time )
  4155. if(max_inactive_time)
  4156. kill();
  4157. if(stepper_inactive_time) {
  4158. if( (millis() - previous_millis_cmd) > stepper_inactive_time )
  4159. {
  4160. if(blocks_queued() == false && ignore_stepper_queue == false) {
  4161. disable_x();
  4162. disable_y();
  4163. disable_z();
  4164. disable_e0();
  4165. disable_e1();
  4166. disable_e2();
  4167. }
  4168. }
  4169. }
  4170. #ifdef CHDK //Check if pin should be set to LOW after M240 set it to HIGH
  4171. if (chdkActive && (millis() - chdkHigh > CHDK_DELAY))
  4172. {
  4173. chdkActive = false;
  4174. WRITE(CHDK, LOW);
  4175. }
  4176. #endif
  4177. #if defined(KILL_PIN) && KILL_PIN > -1
  4178. // Check if the kill button was pressed and wait just in case it was an accidental
  4179. // key kill key press
  4180. // -------------------------------------------------------------------------------
  4181. if( 0 == READ(KILL_PIN) )
  4182. {
  4183. killCount++;
  4184. }
  4185. else if (killCount > 0)
  4186. {
  4187. killCount--;
  4188. }
  4189. // Exceeded threshold and we can confirm that it was not accidental
  4190. // KILL the machine
  4191. // ----------------------------------------------------------------
  4192. if ( killCount >= KILL_DELAY)
  4193. {
  4194. kill();
  4195. }
  4196. #endif
  4197. #if defined(HOME_PIN) && HOME_PIN > -1
  4198. // Check to see if we have to home, use poor man's debouncer
  4199. // ---------------------------------------------------------
  4200. if ( 0 == READ(HOME_PIN) )
  4201. {
  4202. if (homeDebounceCount == 0)
  4203. {
  4204. enquecommand_P((PSTR("G28")));
  4205. homeDebounceCount++;
  4206. LCD_ALERTMESSAGERPGM(MSG_AUTO_HOME);
  4207. }
  4208. else if (homeDebounceCount < HOME_DEBOUNCE_DELAY)
  4209. {
  4210. homeDebounceCount++;
  4211. }
  4212. else
  4213. {
  4214. homeDebounceCount = 0;
  4215. }
  4216. }
  4217. #endif
  4218. #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
  4219. controllerFan(); //Check if fan should be turned on to cool stepper drivers down
  4220. #endif
  4221. #ifdef EXTRUDER_RUNOUT_PREVENT
  4222. if( (millis() - previous_millis_cmd) > EXTRUDER_RUNOUT_SECONDS*1000 )
  4223. if(degHotend(active_extruder)>EXTRUDER_RUNOUT_MINTEMP)
  4224. {
  4225. bool oldstatus=READ(E0_ENABLE_PIN);
  4226. enable_e0();
  4227. float oldepos=current_position[E_AXIS];
  4228. float oldedes=destination[E_AXIS];
  4229. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS],
  4230. destination[E_AXIS]+EXTRUDER_RUNOUT_EXTRUDE*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS],
  4231. EXTRUDER_RUNOUT_SPEED/60.*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS], active_extruder);
  4232. current_position[E_AXIS]=oldepos;
  4233. destination[E_AXIS]=oldedes;
  4234. plan_set_e_position(oldepos);
  4235. previous_millis_cmd=millis();
  4236. st_synchronize();
  4237. WRITE(E0_ENABLE_PIN,oldstatus);
  4238. }
  4239. #endif
  4240. #if defined(DUAL_X_CARRIAGE)
  4241. // handle delayed move timeout
  4242. if (delayed_move_time != 0 && (millis() - delayed_move_time) > 1000 && Stopped == false)
  4243. {
  4244. // travel moves have been received so enact them
  4245. delayed_move_time = 0xFFFFFFFFUL; // force moves to be done
  4246. memcpy(destination,current_position,sizeof(destination));
  4247. prepare_move();
  4248. }
  4249. #endif
  4250. #ifdef TEMP_STAT_LEDS
  4251. handle_status_leds();
  4252. #endif
  4253. check_axes_activity();
  4254. }
  4255. void kill()
  4256. {
  4257. cli(); // Stop interrupts
  4258. disable_heater();
  4259. disable_x();
  4260. disable_y();
  4261. disable_z();
  4262. disable_e0();
  4263. disable_e1();
  4264. disable_e2();
  4265. #if defined(PS_ON_PIN) && PS_ON_PIN > -1
  4266. pinMode(PS_ON_PIN,INPUT);
  4267. #endif
  4268. SERIAL_ERROR_START;
  4269. SERIAL_ERRORLNRPGM(MSG_ERR_KILLED);
  4270. LCD_ALERTMESSAGERPGM(MSG_KILLED);
  4271. // FMC small patch to update the LCD before ending
  4272. sei(); // enable interrupts
  4273. for ( int i=5; i--; lcd_update())
  4274. {
  4275. delay(200);
  4276. }
  4277. cli(); // disable interrupts
  4278. suicide();
  4279. while(1) { /* Intentionally left empty */ } // Wait for reset
  4280. }
  4281. void Stop()
  4282. {
  4283. disable_heater();
  4284. if(Stopped == false) {
  4285. Stopped = true;
  4286. Stopped_gcode_LastN = gcode_LastN; // Save last g_code for restart
  4287. SERIAL_ERROR_START;
  4288. SERIAL_ERRORLNRPGM(MSG_ERR_STOPPED);
  4289. LCD_MESSAGERPGM(MSG_STOPPED);
  4290. }
  4291. }
  4292. bool IsStopped() { return Stopped; };
  4293. #ifdef FAST_PWM_FAN
  4294. void setPwmFrequency(uint8_t pin, int val)
  4295. {
  4296. val &= 0x07;
  4297. switch(digitalPinToTimer(pin))
  4298. {
  4299. #if defined(TCCR0A)
  4300. case TIMER0A:
  4301. case TIMER0B:
  4302. // TCCR0B &= ~(_BV(CS00) | _BV(CS01) | _BV(CS02));
  4303. // TCCR0B |= val;
  4304. break;
  4305. #endif
  4306. #if defined(TCCR1A)
  4307. case TIMER1A:
  4308. case TIMER1B:
  4309. // TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
  4310. // TCCR1B |= val;
  4311. break;
  4312. #endif
  4313. #if defined(TCCR2)
  4314. case TIMER2:
  4315. case TIMER2:
  4316. TCCR2 &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
  4317. TCCR2 |= val;
  4318. break;
  4319. #endif
  4320. #if defined(TCCR2A)
  4321. case TIMER2A:
  4322. case TIMER2B:
  4323. TCCR2B &= ~(_BV(CS20) | _BV(CS21) | _BV(CS22));
  4324. TCCR2B |= val;
  4325. break;
  4326. #endif
  4327. #if defined(TCCR3A)
  4328. case TIMER3A:
  4329. case TIMER3B:
  4330. case TIMER3C:
  4331. TCCR3B &= ~(_BV(CS30) | _BV(CS31) | _BV(CS32));
  4332. TCCR3B |= val;
  4333. break;
  4334. #endif
  4335. #if defined(TCCR4A)
  4336. case TIMER4A:
  4337. case TIMER4B:
  4338. case TIMER4C:
  4339. TCCR4B &= ~(_BV(CS40) | _BV(CS41) | _BV(CS42));
  4340. TCCR4B |= val;
  4341. break;
  4342. #endif
  4343. #if defined(TCCR5A)
  4344. case TIMER5A:
  4345. case TIMER5B:
  4346. case TIMER5C:
  4347. TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52));
  4348. TCCR5B |= val;
  4349. break;
  4350. #endif
  4351. }
  4352. }
  4353. #endif //FAST_PWM_FAN
  4354. bool setTargetedHotend(int code){
  4355. tmp_extruder = active_extruder;
  4356. if(code_seen('T')) {
  4357. tmp_extruder = code_value();
  4358. if(tmp_extruder >= EXTRUDERS) {
  4359. SERIAL_ECHO_START;
  4360. switch(code){
  4361. case 104:
  4362. SERIAL_ECHO(MSG_M104_INVALID_EXTRUDER);
  4363. break;
  4364. case 105:
  4365. SERIAL_ECHO(MSG_M105_INVALID_EXTRUDER);
  4366. break;
  4367. case 109:
  4368. SERIAL_ECHO(MSG_M109_INVALID_EXTRUDER);
  4369. break;
  4370. case 218:
  4371. SERIAL_ECHO(MSG_M218_INVALID_EXTRUDER);
  4372. break;
  4373. case 221:
  4374. SERIAL_ECHO(MSG_M221_INVALID_EXTRUDER);
  4375. break;
  4376. }
  4377. SERIAL_ECHOLN(tmp_extruder);
  4378. return true;
  4379. }
  4380. }
  4381. return false;
  4382. }
  4383. float calculate_volumetric_multiplier(float diameter) {
  4384. float area = .0;
  4385. float radius = .0;
  4386. radius = diameter * .5;
  4387. if (! volumetric_enabled || radius == 0) {
  4388. area = 1;
  4389. }
  4390. else {
  4391. area = M_PI * pow(radius, 2);
  4392. }
  4393. return 1.0 / area;
  4394. }
  4395. void calculate_volumetric_multipliers() {
  4396. volumetric_multiplier[0] = calculate_volumetric_multiplier(filament_size[0]);
  4397. #if EXTRUDERS > 1
  4398. volumetric_multiplier[1] = calculate_volumetric_multiplier(filament_size[1]);
  4399. #if EXTRUDERS > 2
  4400. volumetric_multiplier[2] = calculate_volumetric_multiplier(filament_size[2]);
  4401. #endif
  4402. #endif
  4403. }