My Marlin configs for Fabrikator Mini and CTC i3 Pro B
You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

Marlin_main.cpp 187KB

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