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

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812181318141815181618171818181918201821182218231824182518261827182818291830183118321833183418351836183718381839184018411842184318441845184618471848184918501851185218531854185518561857185818591860186118621863186418651866186718681869187018711872187318741875187618771878187918801881188218831884188518861887188818891890189118921893189418951896189718981899190019011902190319041905190619071908190919101911191219131914191519161917191819191920192119221923192419251926192719281929193019311932193319341935193619371938193919401941194219431944194519461947194819491950195119521953195419551956195719581959196019611962196319641965196619671968196919701971197219731974197519761977197819791980198119821983198419851986198719881989199019911992199319941995199619971998199920002001200220032004200520062007200820092010201120122013201420152016201720182019202020212022202320242025202620272028202920302031203220332034203520362037203820392040204120422043204420452046204720482049205020512052205320542055205620572058205920602061206220632064206520662067206820692070207120722073207420752076207720782079208020812082208320842085208620872088208920902091209220932094209520962097209820992100210121022103210421052106210721082109211021112112211321142115211621172118211921202121212221232124212521262127212821292130213121322133213421352136213721382139214021412142214321442145214621472148214921502151215221532154215521562157215821592160216121622163216421652166216721682169217021712172217321742175217621772178217921802181218221832184218521862187218821892190219121922193219421952196219721982199220022012202220322042205220622072208220922102211221222132214221522162217221822192220222122222223222422252226222722282229223022312232223322342235223622372238223922402241224222432244224522462247224822492250225122522253225422552256225722582259226022612262226322642265226622672268226922702271227222732274227522762277227822792280228122822283228422852286228722882289229022912292229322942295229622972298229923002301230223032304230523062307230823092310231123122313231423152316231723182319232023212322232323242325232623272328232923302331233223332334233523362337233823392340234123422343234423452346234723482349235023512352235323542355235623572358235923602361236223632364236523662367236823692370237123722373237423752376237723782379238023812382238323842385238623872388238923902391239223932394239523962397239823992400240124022403240424052406240724082409241024112412241324142415241624172418241924202421242224232424242524262427242824292430243124322433243424352436243724382439244024412442244324442445244624472448244924502451245224532454245524562457245824592460246124622463246424652466246724682469247024712472247324742475247624772478247924802481248224832484248524862487248824892490249124922493249424952496249724982499250025012502250325042505250625072508250925102511251225132514251525162517251825192520252125222523252425252526252725282529253025312532253325342535253625372538253925402541254225432544254525462547254825492550255125522553255425552556255725582559256025612562256325642565256625672568256925702571257225732574257525762577257825792580258125822583258425852586258725882589259025912592259325942595259625972598259926002601260226032604260526062607260826092610261126122613261426152616261726182619262026212622262326242625262626272628262926302631263226332634263526362637263826392640264126422643264426452646264726482649265026512652265326542655265626572658265926602661266226632664266526662667266826692670267126722673267426752676267726782679268026812682268326842685268626872688268926902691269226932694269526962697269826992700270127022703270427052706270727082709271027112712271327142715271627172718271927202721272227232724272527262727272827292730273127322733273427352736273727382739274027412742274327442745274627472748274927502751275227532754275527562757275827592760276127622763276427652766276727682769277027712772277327742775277627772778277927802781278227832784278527862787278827892790279127922793279427952796279727982799280028012802280328042805280628072808280928102811281228132814281528162817281828192820282128222823282428252826282728282829283028312832283328342835283628372838283928402841284228432844284528462847284828492850285128522853285428552856285728582859286028612862286328642865286628672868286928702871287228732874287528762877287828792880288128822883288428852886288728882889289028912892289328942895289628972898289929002901290229032904290529062907290829092910291129122913291429152916291729182919292029212922292329242925292629272928292929302931293229332934293529362937293829392940294129422943294429452946294729482949295029512952295329542955295629572958295929602961296229632964296529662967296829692970297129722973297429752976297729782979298029812982298329842985298629872988298929902991299229932994299529962997299829993000300130023003300430053006300730083009301030113012301330143015301630173018301930203021302230233024302530263027302830293030303130323033303430353036303730383039304030413042304330443045304630473048304930503051305230533054305530563057305830593060306130623063306430653066306730683069307030713072307330743075307630773078307930803081308230833084308530863087308830893090309130923093309430953096309730983099310031013102310331043105310631073108310931103111311231133114311531163117311831193120312131223123312431253126312731283129313031313132313331343135313631373138313931403141314231433144314531463147314831493150315131523153315431553156315731583159316031613162316331643165316631673168316931703171317231733174317531763177317831793180318131823183318431853186318731883189319031913192319331943195319631973198319932003201320232033204320532063207320832093210321132123213321432153216321732183219322032213222322332243225322632273228322932303231323232333234323532363237323832393240324132423243324432453246324732483249325032513252325332543255325632573258325932603261326232633264326532663267326832693270327132723273327432753276327732783279328032813282328332843285328632873288328932903291329232933294329532963297329832993300330133023303330433053306330733083309331033113312331333143315331633173318331933203321332233233324332533263327332833293330333133323333333433353336333733383339334033413342334333443345334633473348334933503351335233533354335533563357335833593360336133623363336433653366336733683369337033713372337333743375337633773378337933803381338233833384338533863387338833893390339133923393339433953396339733983399340034013402340334043405340634073408340934103411341234133414341534163417341834193420342134223423342434253426342734283429343034313432343334343435343634373438343934403441344234433444344534463447344834493450345134523453345434553456345734583459346034613462346334643465346634673468346934703471347234733474347534763477347834793480348134823483348434853486348734883489349034913492349334943495349634973498349935003501350235033504350535063507350835093510351135123513351435153516351735183519352035213522352335243525352635273528352935303531353235333534353535363537353835393540354135423543354435453546354735483549355035513552355335543555355635573558355935603561356235633564356535663567356835693570357135723573357435753576357735783579358035813582358335843585358635873588358935903591359235933594359535963597359835993600360136023603360436053606360736083609361036113612361336143615361636173618361936203621362236233624362536263627362836293630363136323633363436353636363736383639364036413642364336443645364636473648364936503651365236533654365536563657365836593660366136623663366436653666366736683669367036713672367336743675367636773678367936803681368236833684368536863687368836893690369136923693369436953696369736983699370037013702370337043705370637073708370937103711371237133714371537163717371837193720372137223723372437253726372737283729373037313732373337343735373637373738373937403741374237433744374537463747374837493750375137523753375437553756375737583759376037613762376337643765376637673768376937703771377237733774377537763777377837793780378137823783378437853786378737883789379037913792379337943795379637973798379938003801380238033804380538063807380838093810381138123813381438153816381738183819382038213822382338243825382638273828382938303831383238333834383538363837383838393840384138423843384438453846384738483849385038513852385338543855385638573858385938603861386238633864386538663867386838693870387138723873387438753876387738783879388038813882388338843885388638873888388938903891389238933894389538963897389838993900390139023903390439053906390739083909391039113912391339143915391639173918391939203921392239233924392539263927392839293930393139323933393439353936393739383939394039413942394339443945394639473948394939503951395239533954395539563957395839593960396139623963396439653966396739683969397039713972397339743975397639773978397939803981398239833984398539863987398839893990399139923993399439953996399739983999400040014002400340044005400640074008400940104011401240134014401540164017401840194020402140224023402440254026402740284029403040314032403340344035403640374038403940404041404240434044404540464047404840494050405140524053405440554056405740584059406040614062406340644065406640674068406940704071407240734074407540764077407840794080408140824083408440854086408740884089409040914092409340944095409640974098409941004101410241034104410541064107410841094110411141124113411441154116411741184119412041214122412341244125412641274128412941304131413241334134413541364137413841394140414141424143414441454146414741484149415041514152415341544155415641574158415941604161416241634164416541664167416841694170417141724173417441754176417741784179418041814182418341844185418641874188418941904191419241934194419541964197419841994200420142024203420442054206420742084209421042114212421342144215421642174218421942204221422242234224422542264227422842294230423142324233423442354236423742384239424042414242424342444245424642474248424942504251425242534254425542564257425842594260426142624263426442654266426742684269427042714272427342744275427642774278427942804281428242834284428542864287428842894290429142924293429442954296429742984299430043014302430343044305430643074308430943104311431243134314431543164317431843194320432143224323432443254326432743284329433043314332433343344335433643374338433943404341434243434344434543464347434843494350435143524353435443554356435743584359436043614362436343644365436643674368436943704371437243734374437543764377437843794380438143824383438443854386438743884389439043914392439343944395439643974398439944004401440244034404440544064407440844094410441144124413441444154416441744184419442044214422442344244425442644274428442944304431443244334434443544364437443844394440444144424443444444454446444744484449445044514452445344544455445644574458445944604461446244634464446544664467446844694470447144724473447444754476447744784479448044814482448344844485448644874488448944904491449244934494449544964497449844994500450145024503450445054506450745084509451045114512451345144515451645174518451945204521452245234524452545264527452845294530453145324533453445354536453745384539454045414542454345444545454645474548454945504551455245534554455545564557455845594560456145624563456445654566456745684569457045714572457345744575457645774578457945804581458245834584458545864587458845894590459145924593459445954596459745984599460046014602460346044605460646074608460946104611461246134614461546164617461846194620462146224623462446254626462746284629463046314632463346344635463646374638463946404641464246434644464546464647464846494650465146524653465446554656465746584659466046614662466346644665466646674668466946704671467246734674467546764677467846794680468146824683468446854686468746884689469046914692469346944695469646974698469947004701470247034704470547064707470847094710471147124713471447154716471747184719472047214722472347244725472647274728472947304731473247334734473547364737473847394740474147424743474447454746474747484749475047514752475347544755475647574758475947604761476247634764476547664767476847694770477147724773477447754776477747784779478047814782478347844785478647874788478947904791479247934794479547964797479847994800480148024803480448054806480748084809481048114812481348144815481648174818481948204821482248234824482548264827482848294830483148324833483448354836483748384839484048414842484348444845484648474848484948504851485248534854485548564857485848594860486148624863486448654866486748684869487048714872487348744875487648774878487948804881488248834884488548864887488848894890489148924893489448954896489748984899490049014902490349044905490649074908490949104911491249134914491549164917491849194920492149224923492449254926492749284929493049314932493349344935493649374938493949404941494249434944494549464947494849494950495149524953495449554956495749584959496049614962496349644965496649674968496949704971497249734974497549764977497849794980498149824983498449854986498749884989499049914992499349944995499649974998499950005001500250035004500550065007500850095010501150125013501450155016501750185019502050215022502350245025502650275028502950305031503250335034503550365037503850395040504150425043504450455046504750485049505050515052505350545055505650575058505950605061506250635064506550665067506850695070507150725073507450755076507750785079508050815082508350845085508650875088508950905091509250935094509550965097509850995100510151025103510451055106510751085109511051115112511351145115511651175118511951205121512251235124512551265127512851295130513151325133513451355136513751385139514051415142514351445145514651475148514951505151515251535154515551565157515851595160516151625163516451655166516751685169517051715172517351745175517651775178517951805181518251835184518551865187518851895190519151925193519451955196519751985199520052015202520352045205520652075208520952105211521252135214521552165217521852195220522152225223522452255226522752285229523052315232523352345235523652375238523952405241524252435244524552465247524852495250525152525253525452555256525752585259526052615262526352645265526652675268526952705271527252735274527552765277527852795280528152825283528452855286528752885289529052915292529352945295529652975298529953005301530253035304530553065307530853095310531153125313531453155316531753185319532053215322532353245325532653275328532953305331533253335334533553365337533853395340534153425343534453455346534753485349535053515352535353545355535653575358535953605361536253635364536553665367536853695370537153725373537453755376537753785379538053815382538353845385538653875388538953905391539253935394539553965397539853995400540154025403540454055406540754085409541054115412541354145415541654175418541954205421542254235424542554265427542854295430543154325433543454355436543754385439544054415442544354445445544654475448544954505451545254535454545554565457545854595460546154625463546454655466546754685469547054715472547354745475547654775478547954805481548254835484548554865487548854895490549154925493549454955496549754985499550055015502550355045505550655075508550955105511551255135514551555165517551855195520552155225523552455255526552755285529553055315532553355345535553655375538553955405541554255435544554555465547554855495550555155525553555455555556555755585559556055615562556355645565556655675568556955705571557255735574557555765577557855795580558155825583558455855586558755885589559055915592559355945595559655975598559956005601560256035604560556065607560856095610561156125613561456155616561756185619562056215622562356245625562656275628562956305631563256335634563556365637563856395640564156425643564456455646564756485649565056515652565356545655565656575658565956605661566256635664566556665667566856695670567156725673567456755676567756785679568056815682568356845685568656875688568956905691569256935694569556965697569856995700570157025703570457055706570757085709571057115712571357145715571657175718571957205721572257235724572557265727572857295730573157325733573457355736573757385739574057415742574357445745574657475748574957505751575257535754575557565757575857595760576157625763576457655766576757685769577057715772577357745775577657775778577957805781578257835784578557865787578857895790579157925793579457955796579757985799580058015802580358045805580658075808580958105811581258135814581558165817581858195820582158225823582458255826582758285829583058315832583358345835583658375838583958405841584258435844584558465847584858495850585158525853585458555856585758585859586058615862586358645865586658675868586958705871587258735874587558765877587858795880588158825883588458855886588758885889589058915892589358945895589658975898589959005901590259035904590559065907590859095910591159125913591459155916591759185919592059215922592359245925592659275928592959305931593259335934593559365937593859395940594159425943594459455946594759485949595059515952595359545955595659575958595959605961596259635964596559665967596859695970597159725973597459755976597759785979598059815982598359845985598659875988598959905991599259935994599559965997599859996000600160026003600460056006600760086009601060116012601360146015601660176018601960206021602260236024602560266027602860296030603160326033603460356036603760386039604060416042604360446045604660476048604960506051605260536054605560566057605860596060606160626063606460656066606760686069607060716072607360746075607660776078607960806081608260836084608560866087608860896090609160926093609460956096609760986099610061016102610361046105610661076108610961106111611261136114611561166117611861196120612161226123612461256126612761286129613061316132613361346135613661376138613961406141614261436144614561466147614861496150615161526153615461556156615761586159616061616162616361646165616661676168616961706171617261736174617561766177617861796180618161826183618461856186618761886189619061916192619361946195619661976198619962006201620262036204620562066207620862096210621162126213621462156216621762186219622062216222622362246225622662276228622962306231623262336234623562366237623862396240624162426243624462456246624762486249625062516252625362546255625662576258625962606261626262636264626562666267626862696270627162726273627462756276627762786279628062816282628362846285628662876288628962906291629262936294629562966297629862996300630163026303630463056306630763086309631063116312631363146315631663176318631963206321632263236324632563266327632863296330633163326333633463356336633763386339634063416342634363446345634663476348634963506351635263536354635563566357635863596360636163626363636463656366636763686369637063716372637363746375637663776378637963806381638263836384638563866387638863896390639163926393639463956396639763986399640064016402640364046405640664076408640964106411641264136414641564166417641864196420642164226423642464256426642764286429643064316432643364346435643664376438643964406441644264436444644564466447644864496450645164526453645464556456645764586459646064616462646364646465646664676468646964706471647264736474647564766477647864796480648164826483648464856486648764886489649064916492649364946495649664976498649965006501650265036504650565066507650865096510651165126513651465156516651765186519652065216522652365246525652665276528652965306531653265336534653565366537653865396540654165426543654465456546654765486549655065516552655365546555655665576558655965606561656265636564656565666567656865696570657165726573657465756576657765786579658065816582658365846585658665876588658965906591659265936594659565966597659865996600660166026603660466056606660766086609661066116612661366146615661666176618661966206621662266236624662566266627662866296630663166326633663466356636663766386639664066416642664366446645664666476648664966506651665266536654665566566657665866596660666166626663666466656666666766686669667066716672667366746675667666776678667966806681668266836684668566866687668866896690669166926693669466956696669766986699670067016702670367046705670667076708670967106711671267136714671567166717671867196720672167226723672467256726672767286729673067316732673367346735673667376738673967406741674267436744674567466747674867496750675167526753675467556756675767586759676067616762676367646765676667676768676967706771677267736774677567766777677867796780678167826783678467856786678767886789679067916792679367946795679667976798679968006801680268036804680568066807680868096810681168126813681468156816681768186819682068216822682368246825682668276828682968306831683268336834683568366837683868396840684168426843684468456846684768486849685068516852685368546855685668576858685968606861686268636864686568666867686868696870687168726873687468756876687768786879688068816882688368846885688668876888688968906891689268936894689568966897689868996900690169026903690469056906690769086909691069116912691369146915691669176918691969206921692269236924692569266927692869296930693169326933693469356936693769386939694069416942694369446945694669476948694969506951695269536954695569566957695869596960696169626963696469656966696769686969697069716972697369746975697669776978697969806981698269836984698569866987698869896990699169926993699469956996699769986999700070017002700370047005700670077008700970107011701270137014701570167017701870197020702170227023702470257026702770287029703070317032703370347035703670377038703970407041704270437044704570467047704870497050705170527053705470557056705770587059706070617062706370647065706670677068706970707071707270737074707570767077707870797080708170827083708470857086708770887089709070917092709370947095709670977098709971007101710271037104710571067107710871097110711171127113711471157116711771187119712071217122712371247125712671277128712971307131713271337134713571367137713871397140714171427143714471457146714771487149715071517152715371547155715671577158715971607161716271637164716571667167716871697170717171727173717471757176717771787179718071817182718371847185718671877188718971907191719271937194719571967197719871997200720172027203720472057206720772087209721072117212721372147215721672177218721972207221722272237224722572267227722872297230723172327233723472357236723772387239724072417242724372447245724672477248724972507251725272537254725572567257725872597260726172627263726472657266726772687269727072717272727372747275727672777278727972807281728272837284728572867287728872897290729172927293729472957296729772987299730073017302730373047305730673077308730973107311731273137314731573167317731873197320732173227323732473257326732773287329733073317332733373347335733673377338733973407341734273437344734573467347734873497350735173527353735473557356735773587359736073617362736373647365736673677368736973707371737273737374737573767377737873797380738173827383738473857386738773887389739073917392739373947395739673977398739974007401740274037404740574067407740874097410741174127413741474157416741774187419742074217422742374247425742674277428742974307431743274337434743574367437743874397440744174427443744474457446744774487449745074517452745374547455745674577458745974607461746274637464746574667467746874697470747174727473747474757476747774787479748074817482748374847485748674877488748974907491749274937494749574967497749874997500750175027503750475057506750775087509751075117512751375147515751675177518751975207521752275237524752575267527752875297530753175327533753475357536753775387539754075417542754375447545754675477548754975507551755275537554755575567557755875597560756175627563756475657566756775687569757075717572757375747575757675777578757975807581758275837584758575867587758875897590759175927593759475957596759775987599760076017602760376047605760676077608760976107611761276137614761576167617761876197620762176227623762476257626762776287629763076317632763376347635763676377638763976407641764276437644764576467647764876497650765176527653765476557656765776587659766076617662766376647665766676677668766976707671767276737674767576767677767876797680768176827683768476857686768776887689769076917692769376947695769676977698769977007701770277037704770577067707770877097710771177127713771477157716771777187719772077217722772377247725772677277728772977307731773277337734773577367737773877397740774177427743774477457746774777487749775077517752775377547755775677577758775977607761776277637764776577667767776877697770777177727773777477757776777777787779778077817782778377847785778677877788778977907791779277937794779577967797779877997800780178027803780478057806780778087809781078117812781378147815781678177818781978207821782278237824782578267827782878297830783178327833783478357836783778387839784078417842784378447845784678477848784978507851785278537854785578567857785878597860786178627863786478657866786778687869787078717872787378747875787678777878787978807881788278837884788578867887788878897890789178927893789478957896789778987899790079017902790379047905790679077908790979107911791279137914791579167917791879197920792179227923792479257926792779287929793079317932793379347935793679377938793979407941794279437944794579467947794879497950795179527953795479557956795779587959796079617962796379647965796679677968796979707971797279737974797579767977797879797980798179827983798479857986798779887989799079917992799379947995799679977998799980008001800280038004800580068007800880098010801180128013801480158016801780188019802080218022802380248025802680278028802980308031803280338034803580368037803880398040804180428043804480458046804780488049805080518052805380548055805680578058805980608061806280638064806580668067806880698070807180728073807480758076807780788079808080818082808380848085808680878088808980908091809280938094809580968097809880998100810181028103810481058106810781088109811081118112811381148115811681178118811981208121812281238124812581268127812881298130813181328133813481358136813781388139814081418142814381448145814681478148814981508151815281538154815581568157815881598160816181628163816481658166816781688169817081718172817381748175817681778178817981808181818281838184818581868187818881898190819181928193819481958196819781988199820082018202820382048205820682078208820982108211821282138214821582168217821882198220822182228223822482258226822782288229823082318232823382348235823682378238823982408241
  1. /**
  2. * Marlin 3D Printer Firmware
  3. * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
  4. *
  5. * Based on Sprinter and grbl.
  6. * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
  7. *
  8. * This program is free software: you can redistribute it and/or modify
  9. * it under the terms of the GNU General Public License as published by
  10. * the Free Software Foundation, either version 3 of the License, or
  11. * (at your option) any later version.
  12. *
  13. * This program is distributed in the hope that it will be useful,
  14. * but WITHOUT ANY WARRANTY; without even the implied warranty of
  15. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  16. * GNU General Public License for more details.
  17. *
  18. * You should have received a copy of the GNU General Public License
  19. * along with this program. If not, see <http://www.gnu.org/licenses/>.
  20. *
  21. */
  22. /**
  23. *
  24. * About Marlin
  25. *
  26. * This firmware is a mashup between Sprinter and grbl.
  27. * - https://github.com/kliment/Sprinter
  28. * - https://github.com/simen/grbl/tree
  29. *
  30. * It has preliminary support for Matthew Roberts advance algorithm
  31. * - http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
  32. */
  33. #include "Marlin.h"
  34. #if ENABLED(AUTO_BED_LEVELING_FEATURE)
  35. #include "vector_3.h"
  36. #if ENABLED(AUTO_BED_LEVELING_GRID)
  37. #include "qr_solve.h"
  38. #endif
  39. #endif // AUTO_BED_LEVELING_FEATURE
  40. #if ENABLED(MESH_BED_LEVELING)
  41. #include "mesh_bed_leveling.h"
  42. #endif
  43. #if ENABLED(BEZIER_CURVE_SUPPORT)
  44. #include "planner_bezier.h"
  45. #endif
  46. #include "ultralcd.h"
  47. #include "planner.h"
  48. #include "stepper.h"
  49. #include "endstops.h"
  50. #include "temperature.h"
  51. #include "cardreader.h"
  52. #include "configuration_store.h"
  53. #include "language.h"
  54. #include "pins_arduino.h"
  55. #include "math.h"
  56. #include "buzzer.h"
  57. #if ENABLED(USE_WATCHDOG)
  58. #include "watchdog.h"
  59. #endif
  60. #if ENABLED(BLINKM)
  61. #include "blinkm.h"
  62. #include "Wire.h"
  63. #endif
  64. #if HAS_SERVOS
  65. #include "servo.h"
  66. #endif
  67. #if HAS_DIGIPOTSS
  68. #include <SPI.h>
  69. #endif
  70. #if ENABLED(DAC_STEPPER_CURRENT)
  71. #include "stepper_dac.h"
  72. #endif
  73. #if ENABLED(EXPERIMENTAL_I2CBUS)
  74. #include "twibus.h"
  75. #endif
  76. /**
  77. * Look here for descriptions of G-codes:
  78. * - http://linuxcnc.org/handbook/gcode/g-code.html
  79. * - http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
  80. *
  81. * Help us document these G-codes online:
  82. * - https://github.com/MarlinFirmware/Marlin/wiki/G-Code-in-Marlin
  83. * - http://reprap.org/wiki/G-code
  84. *
  85. * -----------------
  86. * Implemented Codes
  87. * -----------------
  88. *
  89. * "G" Codes
  90. *
  91. * G0 -> G1
  92. * G1 - Coordinated Movement X Y Z E
  93. * G2 - CW ARC
  94. * G3 - CCW ARC
  95. * G4 - Dwell S<seconds> or P<milliseconds>
  96. * G5 - Cubic B-spline with XYZE destination and IJPQ offsets
  97. * G10 - retract filament according to settings of M207
  98. * G11 - retract recover filament according to settings of M208
  99. * G28 - Home one or more axes
  100. * G29 - Detailed Z probe, probes the bed at 3 or more points. Will fail if you haven't homed yet.
  101. * G30 - Single Z probe, probes bed at current XY location.
  102. * G31 - Dock sled (Z_PROBE_SLED only)
  103. * G32 - Undock sled (Z_PROBE_SLED only)
  104. * G90 - Use Absolute Coordinates
  105. * G91 - Use Relative Coordinates
  106. * G92 - Set current position to coordinates given
  107. *
  108. * "M" Codes
  109. *
  110. * M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled)
  111. * M1 - Same as M0
  112. * M17 - Enable/Power all stepper motors
  113. * M18 - Disable all stepper motors; same as M84
  114. * M20 - List SD card
  115. * M21 - Init SD card
  116. * M22 - Release SD card
  117. * M23 - Select SD file (M23 filename.g)
  118. * M24 - Start/resume SD print
  119. * M25 - Pause SD print
  120. * M26 - Set SD position in bytes (M26 S12345)
  121. * M27 - Report SD print status
  122. * M28 - Start SD write (M28 filename.g)
  123. * M29 - Stop SD write
  124. * M30 - Delete file from SD (M30 filename.g)
  125. * M31 - Output time since last M109 or SD card start to serial
  126. * M32 - Select file and start SD print (Can be used _while_ printing from SD card files):
  127. * syntax "M32 /path/filename#", or "M32 S<startpos bytes> !filename#"
  128. * Call gcode file : "M32 P !filename#" and return to caller file after finishing (similar to #include).
  129. * The '#' is necessary when calling from within sd files, as it stops buffer prereading
  130. * M33 - Get the longname version of a path
  131. * 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.
  132. * M48 - Measure Z_Probe repeatability. M48 [P # of points] [X position] [Y position] [V_erboseness #] [E_ngage Probe] [L # of legs of travel]
  133. * M75 - Start the print job timer
  134. * M76 - Pause the print job timer
  135. * M77 - Stop the print job timer
  136. * M78 - Show statistical information about the print jobs
  137. * M80 - Turn on Power Supply
  138. * M81 - Turn off Power Supply
  139. * M82 - Set E codes absolute (default)
  140. * M83 - Set E codes relative while in Absolute Coordinates (G90) mode
  141. * M84 - Disable steppers until next move,
  142. * or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
  143. * M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
  144. * M92 - Set planner.axis_steps_per_unit - same syntax as G92
  145. * M104 - Set extruder target temp
  146. * M105 - Read current temp
  147. * M106 - Fan on
  148. * M107 - Fan off
  149. * M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating
  150. * Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling
  151. * IF AUTOTEMP is enabled, S<mintemp> B<maxtemp> F<factor>. Exit autotemp by any M109 without F
  152. * M110 - Set the current line number
  153. * M111 - Set debug flags with S<mask>. See flag bits defined in Marlin.h.
  154. * M112 - Emergency stop
  155. * M113 - Get or set the timeout interval for Host Keepalive "busy" messages
  156. * M114 - Output current position to serial port
  157. * M115 - Capabilities string
  158. * M117 - Display a message on the controller screen
  159. * M119 - Output Endstop status to serial port
  160. * M120 - Enable endstop detection
  161. * M121 - Disable endstop detection
  162. * M126 - Solenoid Air Valve Open (BariCUDA support by jmil)
  163. * M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil)
  164. * M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil)
  165. * M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil)
  166. * M140 - Set bed target temp
  167. * M145 - Set the heatup state H<hotend> B<bed> F<fan speed> for S<material> (0=PLA, 1=ABS)
  168. * 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.
  169. * M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating
  170. * Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
  171. * M200 - set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).:D<millimeters>-
  172. * M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
  173. * M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
  174. * M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
  175. * 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
  176. * 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
  177. * M206 - Set additional homing offset
  178. * M207 - Set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop], stays in mm regardless of M200 setting
  179. * M208 - Set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/min]
  180. * 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.
  181. * M218 - Set hotend offset (in mm): T<extruder_number> X<offset_on_X> Y<offset_on_Y>
  182. * M220 - Set speed factor override percentage: S<factor in percent>
  183. * M221 - Set extrude factor override percentage: S<factor in percent>
  184. * M226 - Wait until the specified pin reaches the state required: P<pin number> S<pin state>
  185. * M240 - Trigger a camera to take a photograph
  186. * M250 - Set LCD contrast C<contrast value> (value 0..63)
  187. * M280 - Set servo position absolute. P: servo index, S: angle or microseconds
  188. * M300 - Play beep sound S<frequency Hz> P<duration ms>
  189. * M301 - Set PID parameters P I and D
  190. * M302 - Allow cold extrudes, or set the minimum extrude S<temperature>.
  191. * M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
  192. * M304 - Set bed PID parameters P I and D
  193. * M380 - Activate solenoid on active extruder
  194. * M381 - Disable all solenoids
  195. * M400 - Finish all moves
  196. * M401 - Lower Z probe if present
  197. * M402 - Raise Z probe if present
  198. * M404 - N<dia in mm> Enter the nominal filament width (3mm, 1.75mm ) or will display nominal filament width without parameters
  199. * M405 - Turn on Filament Sensor extrusion control. Optional D<delay in cm> to set delay in centimeters between sensor and extruder
  200. * M406 - Turn off Filament Sensor extrusion control
  201. * M407 - Display measured filament diameter
  202. * M410 - Quickstop. Abort all the planned moves
  203. * M420 - Enable/Disable Mesh Leveling (with current values) S1=enable S0=disable
  204. * M421 - Set a single Z coordinate in the Mesh Leveling grid. X<mm> Y<mm> Z<mm>
  205. * M428 - Set the home_offset logically based on the current_position
  206. * M500 - Store parameters in EEPROM
  207. * M501 - Read parameters from EEPROM (if you need reset them after you changed them temporarily).
  208. * M502 - Revert to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
  209. * M503 - Print the current settings (from memory not from EEPROM). Use S0 to leave off headings.
  210. * M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
  211. * M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
  212. * M665 - Set delta configurations: L<diagonal rod> R<delta radius> S<segments/s>
  213. * M666 - Set delta endstop adjustment
  214. * M605 - Set dual x-carriage movement mode: S<mode> [ X<duplication x-offset> R<duplication temp offset> ]
  215. * M907 - Set digital trimpot motor current using axis codes.
  216. * M908 - Control digital trimpot directly.
  217. * M909 - DAC_STEPPER_CURRENT: Print digipot/DAC current value
  218. * M910 - DAC_STEPPER_CURRENT: Commit digipot/DAC value to external EEPROM via I2C
  219. * M350 - Set microstepping mode.
  220. * M351 - Toggle MS1 MS2 pins directly.
  221. *
  222. * ************ SCARA Specific - This can change to suit future G-code regulations
  223. * M360 - SCARA calibration: Move to cal-position ThetaA (0 deg calibration)
  224. * M361 - SCARA calibration: Move to cal-position ThetaB (90 deg calibration - steps per degree)
  225. * M362 - SCARA calibration: Move to cal-position PsiA (0 deg calibration)
  226. * M363 - SCARA calibration: Move to cal-position PsiB (90 deg calibration - steps per degree)
  227. * M364 - SCARA calibration: Move to cal-position PSIC (90 deg to Theta calibration position)
  228. * M365 - SCARA calibration: Scaling factor, X, Y, Z axis
  229. * ************* SCARA End ***************
  230. *
  231. * ************ Custom codes - This can change to suit future G-code regulations
  232. * M100 - Watch Free Memory (For Debugging Only)
  233. * M851 - Set Z probe's Z offset (mm above extruder -- The value will always be negative)
  234. * M928 - Start SD logging (M928 filename.g) - ended by M29
  235. * M999 - Restart after being stopped by error
  236. *
  237. * "T" Codes
  238. *
  239. * T0-T3 - Select a tool by index (usually an extruder) [ F<mm/min> ]
  240. *
  241. */
  242. #if ENABLED(M100_FREE_MEMORY_WATCHER)
  243. void gcode_M100();
  244. #endif
  245. #if ENABLED(SDSUPPORT)
  246. CardReader card;
  247. #endif
  248. #if ENABLED(EXPERIMENTAL_I2CBUS)
  249. TWIBus i2c;
  250. #endif
  251. bool Running = true;
  252. uint8_t marlin_debug_flags = DEBUG_NONE;
  253. static float feedrate = 1500.0, saved_feedrate;
  254. float current_position[NUM_AXIS] = { 0.0 };
  255. static float destination[NUM_AXIS] = { 0.0 };
  256. bool axis_known_position[3] = { false };
  257. bool axis_homed[3] = { false };
  258. static long gcode_N, gcode_LastN, Stopped_gcode_LastN = 0;
  259. static char* current_command, *current_command_args;
  260. static int cmd_queue_index_r = 0;
  261. static int cmd_queue_index_w = 0;
  262. static int commands_in_queue = 0;
  263. static char command_queue[BUFSIZE][MAX_CMD_SIZE];
  264. const float homing_feedrate[] = HOMING_FEEDRATE;
  265. bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
  266. int feedrate_multiplier = 100; //100->1 200->2
  267. int saved_feedrate_multiplier;
  268. int extruder_multiplier[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100);
  269. bool volumetric_enabled = false;
  270. float filament_size[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_NOMINAL_FILAMENT_DIA);
  271. float volumetric_multiplier[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0);
  272. // The distance that XYZ has been offset by G92. Reset by G28.
  273. float position_shift[3] = { 0 };
  274. // This offset is added to the configured home position.
  275. // Set by M206, M428, or menu item. Saved to EEPROM.
  276. float home_offset[3] = { 0 };
  277. // Software Endstops. Default to configured limits.
  278. float sw_endstop_min[3] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS };
  279. float sw_endstop_max[3] = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS };
  280. #if FAN_COUNT > 0
  281. int fanSpeeds[FAN_COUNT] = { 0 };
  282. #endif
  283. // The active extruder (tool). Set with T<extruder> command.
  284. uint8_t active_extruder = 0;
  285. // Relative Mode. Enable with G91, disable with G90.
  286. static bool relative_mode = false;
  287. bool cancel_heatup = false;
  288. const char errormagic[] PROGMEM = "Error:";
  289. const char echomagic[] PROGMEM = "echo:";
  290. const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
  291. static int serial_count = 0;
  292. // GCode parameter pointer used by code_seen(), code_value(), etc.
  293. static char* seen_pointer;
  294. // Next Immediate GCode Command pointer. NULL if none.
  295. const char* queued_commands_P = NULL;
  296. const int sensitive_pins[] = SENSITIVE_PINS; ///< Sensitive pin list for M42
  297. // Inactivity shutdown
  298. millis_t previous_cmd_ms = 0;
  299. static millis_t max_inactive_time = 0;
  300. static millis_t stepper_inactive_time = (DEFAULT_STEPPER_DEACTIVE_TIME) * 1000UL;
  301. // Print Job Timer
  302. #if ENABLED(PRINTCOUNTER)
  303. PrintCounter print_job_timer = PrintCounter();
  304. #else
  305. Stopwatch print_job_timer = Stopwatch();
  306. #endif
  307. static uint8_t target_extruder;
  308. #if ENABLED(AUTO_BED_LEVELING_FEATURE)
  309. int xy_travel_speed = XY_TRAVEL_SPEED;
  310. float zprobe_zoffset = Z_PROBE_OFFSET_FROM_EXTRUDER;
  311. bool bed_leveling_in_progress = false;
  312. #endif
  313. #if ENABLED(Z_DUAL_ENDSTOPS) && DISABLED(DELTA)
  314. float z_endstop_adj = 0;
  315. #endif
  316. // Extruder offsets
  317. #if EXTRUDERS > 1
  318. #ifndef EXTRUDER_OFFSET_X
  319. #define EXTRUDER_OFFSET_X { 0 } // X offsets for each extruder
  320. #endif
  321. #ifndef EXTRUDER_OFFSET_Y
  322. #define EXTRUDER_OFFSET_Y { 0 } // Y offsets for each extruder
  323. #endif
  324. float extruder_offset[][EXTRUDERS] = {
  325. EXTRUDER_OFFSET_X,
  326. EXTRUDER_OFFSET_Y
  327. #if ENABLED(DUAL_X_CARRIAGE)
  328. , { 0 } // Z offsets for each extruder
  329. #endif
  330. };
  331. #endif
  332. #if ENABLED(HAS_SERVO_ENDSTOPS)
  333. const int servo_endstop_id[] = SERVO_ENDSTOP_IDS;
  334. const int servo_endstop_angle[][2] = SERVO_ENDSTOP_ANGLES;
  335. #endif
  336. #if ENABLED(BARICUDA)
  337. int baricuda_valve_pressure = 0;
  338. int baricuda_e_to_p_pressure = 0;
  339. #endif
  340. #if ENABLED(FWRETRACT)
  341. bool autoretract_enabled = false;
  342. bool retracted[EXTRUDERS] = { false };
  343. bool retracted_swap[EXTRUDERS] = { false };
  344. float retract_length = RETRACT_LENGTH;
  345. float retract_length_swap = RETRACT_LENGTH_SWAP;
  346. float retract_feedrate = RETRACT_FEEDRATE;
  347. float retract_zlift = RETRACT_ZLIFT;
  348. float retract_recover_length = RETRACT_RECOVER_LENGTH;
  349. float retract_recover_length_swap = RETRACT_RECOVER_LENGTH_SWAP;
  350. float retract_recover_feedrate = RETRACT_RECOVER_FEEDRATE;
  351. #endif // FWRETRACT
  352. #if ENABLED(ULTIPANEL) && HAS_POWER_SWITCH
  353. bool powersupply =
  354. #if ENABLED(PS_DEFAULT_OFF)
  355. false
  356. #else
  357. true
  358. #endif
  359. ;
  360. #endif
  361. #if ENABLED(DELTA)
  362. #define TOWER_1 X_AXIS
  363. #define TOWER_2 Y_AXIS
  364. #define TOWER_3 Z_AXIS
  365. float delta[3] = { 0 };
  366. #define SIN_60 0.8660254037844386
  367. #define COS_60 0.5
  368. float endstop_adj[3] = { 0 };
  369. // these are the default values, can be overriden with M665
  370. float delta_radius = DELTA_RADIUS;
  371. float delta_tower1_x = -SIN_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_1); // front left tower
  372. float delta_tower1_y = -COS_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_1);
  373. float delta_tower2_x = SIN_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_2); // front right tower
  374. float delta_tower2_y = -COS_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_2);
  375. float delta_tower3_x = 0; // back middle tower
  376. float delta_tower3_y = (delta_radius + DELTA_RADIUS_TRIM_TOWER_3);
  377. float delta_diagonal_rod = DELTA_DIAGONAL_ROD;
  378. float delta_diagonal_rod_trim_tower_1 = DELTA_DIAGONAL_ROD_TRIM_TOWER_1;
  379. float delta_diagonal_rod_trim_tower_2 = DELTA_DIAGONAL_ROD_TRIM_TOWER_2;
  380. float delta_diagonal_rod_trim_tower_3 = DELTA_DIAGONAL_ROD_TRIM_TOWER_3;
  381. float delta_diagonal_rod_2_tower_1 = sq(delta_diagonal_rod + delta_diagonal_rod_trim_tower_1);
  382. float delta_diagonal_rod_2_tower_2 = sq(delta_diagonal_rod + delta_diagonal_rod_trim_tower_2);
  383. float delta_diagonal_rod_2_tower_3 = sq(delta_diagonal_rod + delta_diagonal_rod_trim_tower_3);
  384. //float delta_diagonal_rod_2 = sq(delta_diagonal_rod);
  385. float delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND;
  386. #if ENABLED(AUTO_BED_LEVELING_FEATURE)
  387. int delta_grid_spacing[2] = { 0, 0 };
  388. float bed_level[AUTO_BED_LEVELING_GRID_POINTS][AUTO_BED_LEVELING_GRID_POINTS];
  389. #endif
  390. #else
  391. static bool home_all_axis = true;
  392. #endif
  393. #if ENABLED(SCARA)
  394. float delta_segments_per_second = SCARA_SEGMENTS_PER_SECOND;
  395. static float delta[3] = { 0 };
  396. float axis_scaling[3] = { 1, 1, 1 }; // Build size scaling, default to 1
  397. #endif
  398. #if ENABLED(FILAMENT_WIDTH_SENSOR)
  399. //Variables for Filament Sensor input
  400. float filament_width_nominal = DEFAULT_NOMINAL_FILAMENT_DIA; //Set nominal filament width, can be changed with M404
  401. bool filament_sensor = false; //M405 turns on filament_sensor control, M406 turns it off
  402. float filament_width_meas = DEFAULT_MEASURED_FILAMENT_DIA; //Stores the measured filament diameter
  403. int8_t measurement_delay[MAX_MEASUREMENT_DELAY + 1]; //ring buffer to delay measurement store extruder factor after subtracting 100
  404. int filwidth_delay_index1 = 0; //index into ring buffer
  405. int filwidth_delay_index2 = -1; //index into ring buffer - set to -1 on startup to indicate ring buffer needs to be initialized
  406. int meas_delay_cm = MEASUREMENT_DELAY_CM; //distance delay setting
  407. #endif
  408. #if ENABLED(FILAMENT_RUNOUT_SENSOR)
  409. static bool filament_ran_out = false;
  410. #endif
  411. static bool send_ok[BUFSIZE];
  412. #if HAS_SERVOS
  413. Servo servo[NUM_SERVOS];
  414. #endif
  415. #ifdef CHDK
  416. millis_t chdkHigh = 0;
  417. boolean chdkActive = false;
  418. #endif
  419. #if ENABLED(PID_ADD_EXTRUSION_RATE)
  420. int lpq_len = 20;
  421. #endif
  422. #if ENABLED(HOST_KEEPALIVE_FEATURE)
  423. // States for managing Marlin and host communication
  424. // Marlin sends messages if blocked or busy
  425. enum MarlinBusyState {
  426. NOT_BUSY, // Not in a handler
  427. IN_HANDLER, // Processing a GCode
  428. IN_PROCESS, // Known to be blocking command input (as in G29)
  429. PAUSED_FOR_USER, // Blocking pending any input
  430. PAUSED_FOR_INPUT // Blocking pending text input (concept)
  431. };
  432. static MarlinBusyState busy_state = NOT_BUSY;
  433. static millis_t next_busy_signal_ms = 0;
  434. uint8_t host_keepalive_interval = DEFAULT_KEEPALIVE_INTERVAL;
  435. #define KEEPALIVE_STATE(n) do{ busy_state = n; }while(0)
  436. #else
  437. #define host_keepalive() ;
  438. #define KEEPALIVE_STATE(n) ;
  439. #endif // HOST_KEEPALIVE_FEATURE
  440. /**
  441. * ***************************************************************************
  442. * ******************************** FUNCTIONS ********************************
  443. * ***************************************************************************
  444. */
  445. void stop();
  446. void get_available_commands();
  447. void process_next_command();
  448. #if ENABLED(ARC_SUPPORT)
  449. void plan_arc(float target[NUM_AXIS], float* offset, uint8_t clockwise);
  450. #endif
  451. #if ENABLED(BEZIER_CURVE_SUPPORT)
  452. void plan_cubic_move(const float offset[4]);
  453. #endif
  454. void serial_echopair_P(const char* s_P, int v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
  455. void serial_echopair_P(const char* s_P, long v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
  456. void serial_echopair_P(const char* s_P, float v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
  457. void serial_echopair_P(const char* s_P, double v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
  458. void serial_echopair_P(const char* s_P, unsigned long v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
  459. static void report_current_position();
  460. #if ENABLED(DEBUG_LEVELING_FEATURE)
  461. void print_xyz(const char* prefix, const float x, const float y, const float z) {
  462. SERIAL_ECHO(prefix);
  463. SERIAL_ECHOPAIR(": (", x);
  464. SERIAL_ECHOPAIR(", ", y);
  465. SERIAL_ECHOPAIR(", ", z);
  466. SERIAL_ECHOLNPGM(")");
  467. }
  468. void print_xyz(const char* prefix, const float xyz[]) {
  469. print_xyz(prefix, xyz[X_AXIS], xyz[Y_AXIS], xyz[Z_AXIS]);
  470. }
  471. #if ENABLED(AUTO_BED_LEVELING_FEATURE)
  472. void print_xyz(const char* prefix, const vector_3 &xyz) {
  473. print_xyz(prefix, xyz.x, xyz.y, xyz.z);
  474. }
  475. #endif
  476. #define DEBUG_POS(PREFIX,VAR) do{ SERIAL_ECHOPGM(PREFIX); print_xyz(" > " STRINGIFY(VAR), VAR); }while(0)
  477. #endif
  478. #if ENABLED(DELTA) || ENABLED(SCARA)
  479. inline void sync_plan_position_delta() {
  480. #if ENABLED(DEBUG_LEVELING_FEATURE)
  481. if (DEBUGGING(LEVELING)) DEBUG_POS("sync_plan_position_delta", current_position);
  482. #endif
  483. calculate_delta(current_position);
  484. planner.set_position_mm(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS]);
  485. }
  486. #endif
  487. #if ENABLED(SDSUPPORT)
  488. #include "SdFatUtil.h"
  489. int freeMemory() { return SdFatUtil::FreeRam(); }
  490. #else
  491. extern "C" {
  492. extern unsigned int __bss_end;
  493. extern unsigned int __heap_start;
  494. extern void* __brkval;
  495. int freeMemory() {
  496. int free_memory;
  497. if ((int)__brkval == 0)
  498. free_memory = ((int)&free_memory) - ((int)&__bss_end);
  499. else
  500. free_memory = ((int)&free_memory) - ((int)__brkval);
  501. return free_memory;
  502. }
  503. }
  504. #endif //!SDSUPPORT
  505. #if ENABLED(DIGIPOT_I2C)
  506. extern void digipot_i2c_set_current(int channel, float current);
  507. extern void digipot_i2c_init();
  508. #endif
  509. /**
  510. * Inject the next "immediate" command, when possible.
  511. * Return true if any immediate commands remain to inject.
  512. */
  513. static bool drain_queued_commands_P() {
  514. if (queued_commands_P != NULL) {
  515. size_t i = 0;
  516. char c, cmd[30];
  517. strncpy_P(cmd, queued_commands_P, sizeof(cmd) - 1);
  518. cmd[sizeof(cmd) - 1] = '\0';
  519. while ((c = cmd[i]) && c != '\n') i++; // find the end of this gcode command
  520. cmd[i] = '\0';
  521. if (enqueue_and_echo_command(cmd)) { // success?
  522. if (c) // newline char?
  523. queued_commands_P += i + 1; // advance to the next command
  524. else
  525. queued_commands_P = NULL; // nul char? no more commands
  526. }
  527. }
  528. return (queued_commands_P != NULL); // return whether any more remain
  529. }
  530. /**
  531. * Record one or many commands to run from program memory.
  532. * Aborts the current queue, if any.
  533. * Note: drain_queued_commands_P() must be called repeatedly to drain the commands afterwards
  534. */
  535. void enqueue_and_echo_commands_P(const char* pgcode) {
  536. queued_commands_P = pgcode;
  537. drain_queued_commands_P(); // first command executed asap (when possible)
  538. }
  539. void clear_command_queue() {
  540. cmd_queue_index_r = cmd_queue_index_w;
  541. commands_in_queue = 0;
  542. }
  543. /**
  544. * Once a new command is in the ring buffer, call this to commit it
  545. */
  546. inline void _commit_command(bool say_ok) {
  547. send_ok[cmd_queue_index_w] = say_ok;
  548. cmd_queue_index_w = (cmd_queue_index_w + 1) % BUFSIZE;
  549. commands_in_queue++;
  550. }
  551. /**
  552. * Copy a command directly into the main command buffer, from RAM.
  553. * Returns true if successfully adds the command
  554. */
  555. inline bool _enqueuecommand(const char* cmd, bool say_ok=false) {
  556. if (*cmd == ';' || commands_in_queue >= BUFSIZE) return false;
  557. strcpy(command_queue[cmd_queue_index_w], cmd);
  558. _commit_command(say_ok);
  559. return true;
  560. }
  561. void enqueue_and_echo_command_now(const char* cmd) {
  562. while (!enqueue_and_echo_command(cmd)) idle();
  563. }
  564. /**
  565. * Enqueue with Serial Echo
  566. */
  567. bool enqueue_and_echo_command(const char* cmd, bool say_ok/*=false*/) {
  568. if (_enqueuecommand(cmd, say_ok)) {
  569. SERIAL_ECHO_START;
  570. SERIAL_ECHOPGM(MSG_Enqueueing);
  571. SERIAL_ECHO(cmd);
  572. SERIAL_ECHOLNPGM("\"");
  573. return true;
  574. }
  575. return false;
  576. }
  577. void setup_killpin() {
  578. #if HAS_KILL
  579. SET_INPUT(KILL_PIN);
  580. WRITE(KILL_PIN, HIGH);
  581. #endif
  582. }
  583. void setup_filrunoutpin() {
  584. #if HAS_FILRUNOUT
  585. pinMode(FILRUNOUT_PIN, INPUT);
  586. #if ENABLED(ENDSTOPPULLUP_FIL_RUNOUT)
  587. WRITE(FILRUNOUT_PIN, HIGH);
  588. #endif
  589. #endif
  590. }
  591. // Set home pin
  592. void setup_homepin(void) {
  593. #if HAS_HOME
  594. SET_INPUT(HOME_PIN);
  595. WRITE(HOME_PIN, HIGH);
  596. #endif
  597. }
  598. void setup_photpin() {
  599. #if HAS_PHOTOGRAPH
  600. OUT_WRITE(PHOTOGRAPH_PIN, LOW);
  601. #endif
  602. }
  603. void setup_powerhold() {
  604. #if HAS_SUICIDE
  605. OUT_WRITE(SUICIDE_PIN, HIGH);
  606. #endif
  607. #if HAS_POWER_SWITCH
  608. #if ENABLED(PS_DEFAULT_OFF)
  609. OUT_WRITE(PS_ON_PIN, PS_ON_ASLEEP);
  610. #else
  611. OUT_WRITE(PS_ON_PIN, PS_ON_AWAKE);
  612. #endif
  613. #endif
  614. }
  615. void suicide() {
  616. #if HAS_SUICIDE
  617. OUT_WRITE(SUICIDE_PIN, LOW);
  618. #endif
  619. }
  620. void servo_init() {
  621. #if NUM_SERVOS >= 1 && HAS_SERVO_0
  622. servo[0].attach(SERVO0_PIN);
  623. servo[0].detach(); // Just set up the pin. We don't have a position yet. Don't move to a random position.
  624. #endif
  625. #if NUM_SERVOS >= 2 && HAS_SERVO_1
  626. servo[1].attach(SERVO1_PIN);
  627. servo[1].detach();
  628. #endif
  629. #if NUM_SERVOS >= 3 && HAS_SERVO_2
  630. servo[2].attach(SERVO2_PIN);
  631. servo[2].detach();
  632. #endif
  633. #if NUM_SERVOS >= 4 && HAS_SERVO_3
  634. servo[3].attach(SERVO3_PIN);
  635. servo[3].detach();
  636. #endif
  637. #if ENABLED(HAS_SERVO_ENDSTOPS)
  638. endstops.enable_z_probe(false);
  639. /**
  640. * Set position of all defined Servo Endstops
  641. *
  642. * ** UNSAFE! - NEEDS UPDATE! **
  643. *
  644. * The servo might be deployed and positioned too low to stow
  645. * when starting up the machine or rebooting the board.
  646. * There's no way to know where the nozzle is positioned until
  647. * homing has been done - no homing with z-probe without init!
  648. *
  649. */
  650. for (int i = 0; i < 3; i++)
  651. if (servo_endstop_id[i] >= 0)
  652. servo[servo_endstop_id[i]].move(servo_endstop_angle[i][1]);
  653. #endif // HAS_SERVO_ENDSTOPS
  654. }
  655. /**
  656. * Stepper Reset (RigidBoard, et.al.)
  657. */
  658. #if HAS_STEPPER_RESET
  659. void disableStepperDrivers() {
  660. pinMode(STEPPER_RESET_PIN, OUTPUT);
  661. digitalWrite(STEPPER_RESET_PIN, LOW); // drive it down to hold in reset motor driver chips
  662. }
  663. void enableStepperDrivers() { pinMode(STEPPER_RESET_PIN, INPUT); } // set to input, which allows it to be pulled high by pullups
  664. #endif
  665. /**
  666. * Marlin entry-point: Set up before the program loop
  667. * - Set up the kill pin, filament runout, power hold
  668. * - Start the serial port
  669. * - Print startup messages and diagnostics
  670. * - Get EEPROM or default settings
  671. * - Initialize managers for:
  672. * • temperature
  673. * • planner
  674. * • watchdog
  675. * • stepper
  676. * • photo pin
  677. * • servos
  678. * • LCD controller
  679. * • Digipot I2C
  680. * • Z probe sled
  681. * • status LEDs
  682. */
  683. void setup() {
  684. #ifdef DISABLE_JTAG
  685. // Disable JTAG on AT90USB chips to free up pins for IO
  686. MCUCR = 0x80;
  687. MCUCR = 0x80;
  688. #endif
  689. setup_killpin();
  690. setup_filrunoutpin();
  691. setup_powerhold();
  692. #if HAS_STEPPER_RESET
  693. disableStepperDrivers();
  694. #endif
  695. MYSERIAL.begin(BAUDRATE);
  696. SERIAL_PROTOCOLLNPGM("start");
  697. SERIAL_ECHO_START;
  698. // Check startup - does nothing if bootloader sets MCUSR to 0
  699. byte mcu = MCUSR;
  700. if (mcu & 1) SERIAL_ECHOLNPGM(MSG_POWERUP);
  701. if (mcu & 2) SERIAL_ECHOLNPGM(MSG_EXTERNAL_RESET);
  702. if (mcu & 4) SERIAL_ECHOLNPGM(MSG_BROWNOUT_RESET);
  703. if (mcu & 8) SERIAL_ECHOLNPGM(MSG_WATCHDOG_RESET);
  704. if (mcu & 32) SERIAL_ECHOLNPGM(MSG_SOFTWARE_RESET);
  705. MCUSR = 0;
  706. SERIAL_ECHOPGM(MSG_MARLIN);
  707. SERIAL_ECHOLNPGM(" " SHORT_BUILD_VERSION);
  708. #ifdef STRING_DISTRIBUTION_DATE
  709. #ifdef STRING_CONFIG_H_AUTHOR
  710. SERIAL_ECHO_START;
  711. SERIAL_ECHOPGM(MSG_CONFIGURATION_VER);
  712. SERIAL_ECHOPGM(STRING_DISTRIBUTION_DATE);
  713. SERIAL_ECHOPGM(MSG_AUTHOR);
  714. SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR);
  715. SERIAL_ECHOPGM("Compiled: ");
  716. SERIAL_ECHOLNPGM(__DATE__);
  717. #endif // STRING_CONFIG_H_AUTHOR
  718. #endif // STRING_DISTRIBUTION_DATE
  719. SERIAL_ECHO_START;
  720. SERIAL_ECHOPGM(MSG_FREE_MEMORY);
  721. SERIAL_ECHO(freeMemory());
  722. SERIAL_ECHOPGM(MSG_PLANNER_BUFFER_BYTES);
  723. SERIAL_ECHOLN((int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
  724. // Send "ok" after commands by default
  725. for (int8_t i = 0; i < BUFSIZE; i++) send_ok[i] = true;
  726. // loads data from EEPROM if available else uses defaults (and resets step acceleration rate)
  727. Config_RetrieveSettings();
  728. lcd_init();
  729. thermalManager.init(); // Initialize temperature loop
  730. #if ENABLED(DELTA) || ENABLED(SCARA)
  731. // Vital to init kinematic equivalent for X0 Y0 Z0
  732. sync_plan_position_delta();
  733. #endif
  734. #if ENABLED(USE_WATCHDOG)
  735. watchdog_init();
  736. #endif
  737. stepper.init(); // Initialize stepper, this enables interrupts!
  738. setup_photpin();
  739. servo_init();
  740. #if HAS_CONTROLLERFAN
  741. SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
  742. #endif
  743. #if HAS_STEPPER_RESET
  744. enableStepperDrivers();
  745. #endif
  746. #if ENABLED(DIGIPOT_I2C)
  747. digipot_i2c_init();
  748. #endif
  749. #if ENABLED(DAC_STEPPER_CURRENT)
  750. dac_init();
  751. #endif
  752. #if ENABLED(Z_PROBE_SLED)
  753. pinMode(SLED_PIN, OUTPUT);
  754. digitalWrite(SLED_PIN, LOW); // turn it off
  755. #endif // Z_PROBE_SLED
  756. setup_homepin();
  757. #ifdef STAT_LED_RED
  758. pinMode(STAT_LED_RED, OUTPUT);
  759. digitalWrite(STAT_LED_RED, LOW); // turn it off
  760. #endif
  761. #ifdef STAT_LED_BLUE
  762. pinMode(STAT_LED_BLUE, OUTPUT);
  763. digitalWrite(STAT_LED_BLUE, LOW); // turn it off
  764. #endif
  765. }
  766. /**
  767. * The main Marlin program loop
  768. *
  769. * - Save or log commands to SD
  770. * - Process available commands (if not saving)
  771. * - Call heater manager
  772. * - Call inactivity manager
  773. * - Call endstop manager
  774. * - Call LCD update
  775. */
  776. void loop() {
  777. if (commands_in_queue < BUFSIZE) get_available_commands();
  778. #if ENABLED(SDSUPPORT)
  779. card.checkautostart(false);
  780. #endif
  781. if (commands_in_queue) {
  782. #if ENABLED(SDSUPPORT)
  783. if (card.saving) {
  784. char* command = command_queue[cmd_queue_index_r];
  785. if (strstr_P(command, PSTR("M29"))) {
  786. // M29 closes the file
  787. card.closefile();
  788. SERIAL_PROTOCOLLNPGM(MSG_FILE_SAVED);
  789. ok_to_send();
  790. }
  791. else {
  792. // Write the string from the read buffer to SD
  793. card.write_command(command);
  794. if (card.logging)
  795. process_next_command(); // The card is saving because it's logging
  796. else
  797. ok_to_send();
  798. }
  799. }
  800. else
  801. process_next_command();
  802. #else
  803. process_next_command();
  804. #endif // SDSUPPORT
  805. commands_in_queue--;
  806. cmd_queue_index_r = (cmd_queue_index_r + 1) % BUFSIZE;
  807. }
  808. endstops.report_state();
  809. idle();
  810. }
  811. void gcode_line_error(const char* err, bool doFlush = true) {
  812. SERIAL_ERROR_START;
  813. serialprintPGM(err);
  814. SERIAL_ERRORLN(gcode_LastN);
  815. //Serial.println(gcode_N);
  816. if (doFlush) FlushSerialRequestResend();
  817. serial_count = 0;
  818. }
  819. inline void get_serial_commands() {
  820. static char serial_line_buffer[MAX_CMD_SIZE];
  821. static boolean serial_comment_mode = false;
  822. // If the command buffer is empty for too long,
  823. // send "wait" to indicate Marlin is still waiting.
  824. #if defined(NO_TIMEOUTS) && NO_TIMEOUTS > 0
  825. static millis_t last_command_time = 0;
  826. millis_t ms = millis();
  827. if (commands_in_queue == 0 && !MYSERIAL.available() && ELAPSED(ms, last_command_time + NO_TIMEOUTS)) {
  828. SERIAL_ECHOLNPGM(MSG_WAIT);
  829. last_command_time = ms;
  830. }
  831. #endif
  832. /**
  833. * Loop while serial characters are incoming and the queue is not full
  834. */
  835. while (commands_in_queue < BUFSIZE && MYSERIAL.available() > 0) {
  836. char serial_char = MYSERIAL.read();
  837. /**
  838. * If the character ends the line
  839. */
  840. if (serial_char == '\n' || serial_char == '\r') {
  841. serial_comment_mode = false; // end of line == end of comment
  842. if (!serial_count) continue; // skip empty lines
  843. serial_line_buffer[serial_count] = 0; // terminate string
  844. serial_count = 0; //reset buffer
  845. char* command = serial_line_buffer;
  846. while (*command == ' ') command++; // skip any leading spaces
  847. char* npos = (*command == 'N') ? command : NULL; // Require the N parameter to start the line
  848. char* apos = strchr(command, '*');
  849. if (npos) {
  850. boolean M110 = strstr_P(command, PSTR("M110")) != NULL;
  851. if (M110) {
  852. char* n2pos = strchr(command + 4, 'N');
  853. if (n2pos) npos = n2pos;
  854. }
  855. gcode_N = strtol(npos + 1, NULL, 10);
  856. if (gcode_N != gcode_LastN + 1 && !M110) {
  857. gcode_line_error(PSTR(MSG_ERR_LINE_NO));
  858. return;
  859. }
  860. if (apos) {
  861. byte checksum = 0, count = 0;
  862. while (command[count] != '*') checksum ^= command[count++];
  863. if (strtol(apos + 1, NULL, 10) != checksum) {
  864. gcode_line_error(PSTR(MSG_ERR_CHECKSUM_MISMATCH));
  865. return;
  866. }
  867. // if no errors, continue parsing
  868. }
  869. else {
  870. gcode_line_error(PSTR(MSG_ERR_NO_CHECKSUM));
  871. return;
  872. }
  873. gcode_LastN = gcode_N;
  874. // if no errors, continue parsing
  875. }
  876. else if (apos) { // No '*' without 'N'
  877. gcode_line_error(PSTR(MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM), false);
  878. return;
  879. }
  880. // Movement commands alert when stopped
  881. if (IsStopped()) {
  882. char* gpos = strchr(command, 'G');
  883. if (gpos) {
  884. int codenum = strtol(gpos + 1, NULL, 10);
  885. switch (codenum) {
  886. case 0:
  887. case 1:
  888. case 2:
  889. case 3:
  890. SERIAL_ERRORLNPGM(MSG_ERR_STOPPED);
  891. LCD_MESSAGEPGM(MSG_STOPPED);
  892. break;
  893. }
  894. }
  895. }
  896. // If command was e-stop process now
  897. if (strcmp(command, "M112") == 0) kill(PSTR(MSG_KILLED));
  898. #if defined(NO_TIMEOUTS) && NO_TIMEOUTS > 0
  899. last_command_time = ms;
  900. #endif
  901. // Add the command to the queue
  902. _enqueuecommand(serial_line_buffer, true);
  903. }
  904. else if (serial_count >= MAX_CMD_SIZE - 1) {
  905. // Keep fetching, but ignore normal characters beyond the max length
  906. // The command will be injected when EOL is reached
  907. }
  908. else if (serial_char == '\\') { // Handle escapes
  909. if (MYSERIAL.available() > 0) {
  910. // if we have one more character, copy it over
  911. serial_char = MYSERIAL.read();
  912. if (!serial_comment_mode) serial_line_buffer[serial_count++] = serial_char;
  913. }
  914. // otherwise do nothing
  915. }
  916. else { // it's not a newline, carriage return or escape char
  917. if (serial_char == ';') serial_comment_mode = true;
  918. if (!serial_comment_mode) serial_line_buffer[serial_count++] = serial_char;
  919. }
  920. } // queue has space, serial has data
  921. }
  922. #if ENABLED(SDSUPPORT)
  923. inline void get_sdcard_commands() {
  924. static bool stop_buffering = false,
  925. sd_comment_mode = false;
  926. if (!card.sdprinting) return;
  927. /**
  928. * '#' stops reading from SD to the buffer prematurely, so procedural
  929. * macro calls are possible. If it occurs, stop_buffering is triggered
  930. * and the buffer is run dry; this character _can_ occur in serial com
  931. * due to checksums, however, no checksums are used in SD printing.
  932. */
  933. if (commands_in_queue == 0) stop_buffering = false;
  934. uint16_t sd_count = 0;
  935. bool card_eof = card.eof();
  936. while (commands_in_queue < BUFSIZE && !card_eof && !stop_buffering) {
  937. int16_t n = card.get();
  938. char sd_char = (char)n;
  939. card_eof = card.eof();
  940. if (card_eof || n == -1
  941. || sd_char == '\n' || sd_char == '\r'
  942. || ((sd_char == '#' || sd_char == ':') && !sd_comment_mode)
  943. ) {
  944. if (card_eof) {
  945. SERIAL_PROTOCOLLNPGM(MSG_FILE_PRINTED);
  946. print_job_timer.stop();
  947. char time[30];
  948. millis_t t = print_job_timer.duration();
  949. int hours = t / 60 / 60, minutes = (t / 60) % 60;
  950. sprintf_P(time, PSTR("%i " MSG_END_HOUR " %i " MSG_END_MINUTE), hours, minutes);
  951. SERIAL_ECHO_START;
  952. SERIAL_ECHOLN(time);
  953. lcd_setstatus(time, true);
  954. card.printingHasFinished();
  955. card.checkautostart(true);
  956. }
  957. if (sd_char == '#') stop_buffering = true;
  958. sd_comment_mode = false; //for new command
  959. if (!sd_count) continue; //skip empty lines
  960. command_queue[cmd_queue_index_w][sd_count] = '\0'; //terminate string
  961. sd_count = 0; //clear buffer
  962. _commit_command(false);
  963. }
  964. else if (sd_count >= MAX_CMD_SIZE - 1) {
  965. /**
  966. * Keep fetching, but ignore normal characters beyond the max length
  967. * The command will be injected when EOL is reached
  968. */
  969. }
  970. else {
  971. if (sd_char == ';') sd_comment_mode = true;
  972. if (!sd_comment_mode) command_queue[cmd_queue_index_w][sd_count++] = sd_char;
  973. }
  974. }
  975. }
  976. #endif // SDSUPPORT
  977. /**
  978. * Add to the circular command queue the next command from:
  979. * - The command-injection queue (queued_commands_P)
  980. * - The active serial input (usually USB)
  981. * - The SD card file being actively printed
  982. */
  983. void get_available_commands() {
  984. // if any immediate commands remain, don't get other commands yet
  985. if (drain_queued_commands_P()) return;
  986. get_serial_commands();
  987. #if ENABLED(SDSUPPORT)
  988. get_sdcard_commands();
  989. #endif
  990. }
  991. bool code_has_value() {
  992. int i = 1;
  993. char c = seen_pointer[i];
  994. while (c == ' ') c = seen_pointer[++i];
  995. if (c == '-' || c == '+') c = seen_pointer[++i];
  996. if (c == '.') c = seen_pointer[++i];
  997. return NUMERIC(c);
  998. }
  999. float code_value() {
  1000. float ret;
  1001. char* e = strchr(seen_pointer, 'E');
  1002. if (e) {
  1003. *e = 0;
  1004. ret = strtod(seen_pointer + 1, NULL);
  1005. *e = 'E';
  1006. }
  1007. else
  1008. ret = strtod(seen_pointer + 1, NULL);
  1009. return ret;
  1010. }
  1011. long code_value_long() { return strtol(seen_pointer + 1, NULL, 10); }
  1012. int16_t code_value_short() { return (int16_t)strtol(seen_pointer + 1, NULL, 10); }
  1013. bool code_seen(char code) {
  1014. seen_pointer = strchr(current_command_args, code);
  1015. return (seen_pointer != NULL); // Return TRUE if the code-letter was found
  1016. }
  1017. /**
  1018. * Set target_extruder from the T parameter or the active_extruder
  1019. *
  1020. * Returns TRUE if the target is invalid
  1021. */
  1022. bool get_target_extruder_from_command(int code) {
  1023. if (code_seen('T')) {
  1024. short t = code_value_short();
  1025. if (t >= EXTRUDERS) {
  1026. SERIAL_ECHO_START;
  1027. SERIAL_CHAR('M');
  1028. SERIAL_ECHO(code);
  1029. SERIAL_ECHOPAIR(" " MSG_INVALID_EXTRUDER " ", t);
  1030. SERIAL_EOL;
  1031. return true;
  1032. }
  1033. target_extruder = t;
  1034. }
  1035. else
  1036. target_extruder = active_extruder;
  1037. return false;
  1038. }
  1039. #define DEFINE_PGM_READ_ANY(type, reader) \
  1040. static inline type pgm_read_any(const type *p) \
  1041. { return pgm_read_##reader##_near(p); }
  1042. DEFINE_PGM_READ_ANY(float, float);
  1043. DEFINE_PGM_READ_ANY(signed char, byte);
  1044. #define XYZ_CONSTS_FROM_CONFIG(type, array, CONFIG) \
  1045. static const PROGMEM type array##_P[3] = \
  1046. { X_##CONFIG, Y_##CONFIG, Z_##CONFIG }; \
  1047. static inline type array(int axis) \
  1048. { return pgm_read_any(&array##_P[axis]); }
  1049. XYZ_CONSTS_FROM_CONFIG(float, base_min_pos, MIN_POS);
  1050. XYZ_CONSTS_FROM_CONFIG(float, base_max_pos, MAX_POS);
  1051. XYZ_CONSTS_FROM_CONFIG(float, base_home_pos, HOME_POS);
  1052. XYZ_CONSTS_FROM_CONFIG(float, max_length, MAX_LENGTH);
  1053. XYZ_CONSTS_FROM_CONFIG(float, home_bump_mm, HOME_BUMP_MM);
  1054. XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR);
  1055. #if ENABLED(DUAL_X_CARRIAGE)
  1056. #define DXC_FULL_CONTROL_MODE 0
  1057. #define DXC_AUTO_PARK_MODE 1
  1058. #define DXC_DUPLICATION_MODE 2
  1059. static int dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
  1060. static float x_home_pos(int extruder) {
  1061. if (extruder == 0)
  1062. return base_home_pos(X_AXIS) + home_offset[X_AXIS];
  1063. else
  1064. /**
  1065. * In dual carriage mode the extruder offset provides an override of the
  1066. * second X-carriage offset when homed - otherwise X2_HOME_POS is used.
  1067. * This allow soft recalibration of the second extruder offset position
  1068. * without firmware reflash (through the M218 command).
  1069. */
  1070. return (extruder_offset[X_AXIS][1] > 0) ? extruder_offset[X_AXIS][1] : X2_HOME_POS;
  1071. }
  1072. static int x_home_dir(int extruder) {
  1073. return (extruder == 0) ? X_HOME_DIR : X2_HOME_DIR;
  1074. }
  1075. static float inactive_extruder_x_pos = X2_MAX_POS; // used in mode 0 & 1
  1076. static bool active_extruder_parked = false; // used in mode 1 & 2
  1077. static float raised_parked_position[NUM_AXIS]; // used in mode 1
  1078. static millis_t delayed_move_time = 0; // used in mode 1
  1079. static float duplicate_extruder_x_offset = DEFAULT_DUPLICATION_X_OFFSET; // used in mode 2
  1080. static float duplicate_extruder_temp_offset = 0; // used in mode 2
  1081. bool extruder_duplication_enabled = false; // used in mode 2
  1082. #endif //DUAL_X_CARRIAGE
  1083. /**
  1084. * Software endstops can be used to monitor the open end of
  1085. * an axis that has a hardware endstop on the other end. Or
  1086. * they can prevent axes from moving past endstops and grinding.
  1087. *
  1088. * To keep doing their job as the coordinate system changes,
  1089. * the software endstop positions must be refreshed to remain
  1090. * at the same positions relative to the machine.
  1091. */
  1092. static void update_software_endstops(AxisEnum axis) {
  1093. float offs = home_offset[axis] + position_shift[axis];
  1094. #if ENABLED(DUAL_X_CARRIAGE)
  1095. if (axis == X_AXIS) {
  1096. float dual_max_x = max(extruder_offset[X_AXIS][1], X2_MAX_POS);
  1097. if (active_extruder != 0) {
  1098. sw_endstop_min[X_AXIS] = X2_MIN_POS + offs;
  1099. sw_endstop_max[X_AXIS] = dual_max_x + offs;
  1100. return;
  1101. }
  1102. else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) {
  1103. sw_endstop_min[X_AXIS] = base_min_pos(X_AXIS) + offs;
  1104. sw_endstop_max[X_AXIS] = min(base_max_pos(X_AXIS), dual_max_x - duplicate_extruder_x_offset) + offs;
  1105. return;
  1106. }
  1107. }
  1108. else
  1109. #endif
  1110. {
  1111. sw_endstop_min[axis] = base_min_pos(axis) + offs;
  1112. sw_endstop_max[axis] = base_max_pos(axis) + offs;
  1113. }
  1114. }
  1115. /**
  1116. * Change the home offset for an axis, update the current
  1117. * position and the software endstops to retain the same
  1118. * relative distance to the new home.
  1119. *
  1120. * Since this changes the current_position, code should
  1121. * call sync_plan_position soon after this.
  1122. */
  1123. static void set_home_offset(AxisEnum axis, float v) {
  1124. current_position[axis] += v - home_offset[axis];
  1125. home_offset[axis] = v;
  1126. update_software_endstops(axis);
  1127. }
  1128. static void set_axis_is_at_home(AxisEnum axis) {
  1129. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1130. if (DEBUGGING(LEVELING)) {
  1131. SERIAL_ECHOPAIR("set_axis_is_at_home(", axis);
  1132. SERIAL_ECHOLNPGM(") >>>");
  1133. }
  1134. #endif
  1135. position_shift[axis] = 0;
  1136. #if ENABLED(DUAL_X_CARRIAGE)
  1137. if (axis == X_AXIS && (active_extruder != 0 || dual_x_carriage_mode == DXC_DUPLICATION_MODE)) {
  1138. if (active_extruder != 0)
  1139. current_position[X_AXIS] = x_home_pos(active_extruder);
  1140. else
  1141. current_position[X_AXIS] = base_home_pos(X_AXIS) + home_offset[X_AXIS];
  1142. update_software_endstops(X_AXIS);
  1143. return;
  1144. }
  1145. #endif
  1146. #if ENABLED(SCARA)
  1147. if (axis == X_AXIS || axis == Y_AXIS) {
  1148. float homeposition[3];
  1149. for (int i = 0; i < 3; i++) homeposition[i] = base_home_pos(i);
  1150. // SERIAL_ECHOPGM("homeposition[x]= "); SERIAL_ECHO(homeposition[0]);
  1151. // SERIAL_ECHOPGM("homeposition[y]= "); SERIAL_ECHOLN(homeposition[1]);
  1152. /**
  1153. * Works out real Homeposition angles using inverse kinematics,
  1154. * and calculates homing offset using forward kinematics
  1155. */
  1156. calculate_delta(homeposition);
  1157. // SERIAL_ECHOPGM("base Theta= "); SERIAL_ECHO(delta[X_AXIS]);
  1158. // SERIAL_ECHOPGM(" base Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
  1159. for (int i = 0; i < 2; i++) delta[i] -= home_offset[i];
  1160. // SERIAL_ECHOPGM("addhome X="); SERIAL_ECHO(home_offset[X_AXIS]);
  1161. // SERIAL_ECHOPGM(" addhome Y="); SERIAL_ECHO(home_offset[Y_AXIS]);
  1162. // SERIAL_ECHOPGM(" addhome Theta="); SERIAL_ECHO(delta[X_AXIS]);
  1163. // SERIAL_ECHOPGM(" addhome Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
  1164. calculate_SCARA_forward_Transform(delta);
  1165. // SERIAL_ECHOPGM("Delta X="); SERIAL_ECHO(delta[X_AXIS]);
  1166. // SERIAL_ECHOPGM(" Delta Y="); SERIAL_ECHOLN(delta[Y_AXIS]);
  1167. current_position[axis] = delta[axis];
  1168. /**
  1169. * SCARA home positions are based on configuration since the actual
  1170. * limits are determined by the inverse kinematic transform.
  1171. */
  1172. sw_endstop_min[axis] = base_min_pos(axis); // + (delta[axis] - base_home_pos(axis));
  1173. sw_endstop_max[axis] = base_max_pos(axis); // + (delta[axis] - base_home_pos(axis));
  1174. }
  1175. else
  1176. #endif
  1177. {
  1178. current_position[axis] = base_home_pos(axis) + home_offset[axis];
  1179. update_software_endstops(axis);
  1180. #if ENABLED(AUTO_BED_LEVELING_FEATURE) && Z_HOME_DIR < 0
  1181. if (axis == Z_AXIS) {
  1182. current_position[Z_AXIS] -= zprobe_zoffset;
  1183. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1184. if (DEBUGGING(LEVELING)) {
  1185. SERIAL_ECHOPAIR("> zprobe_zoffset==", zprobe_zoffset);
  1186. SERIAL_EOL;
  1187. }
  1188. #endif
  1189. }
  1190. #endif
  1191. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1192. if (DEBUGGING(LEVELING)) {
  1193. SERIAL_ECHOPAIR("> home_offset[axis]==", home_offset[axis]);
  1194. DEBUG_POS("", current_position);
  1195. }
  1196. #endif
  1197. }
  1198. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1199. if (DEBUGGING(LEVELING)) {
  1200. SERIAL_ECHOPAIR("<<< set_axis_is_at_home(", axis);
  1201. SERIAL_ECHOLNPGM(")");
  1202. }
  1203. #endif
  1204. }
  1205. /**
  1206. * Some planner shorthand inline functions
  1207. */
  1208. inline void set_homing_bump_feedrate(AxisEnum axis) {
  1209. const int homing_bump_divisor[] = HOMING_BUMP_DIVISOR;
  1210. int hbd = homing_bump_divisor[axis];
  1211. if (hbd < 1) {
  1212. hbd = 10;
  1213. SERIAL_ECHO_START;
  1214. SERIAL_ECHOLNPGM("Warning: Homing Bump Divisor < 1");
  1215. }
  1216. feedrate = homing_feedrate[axis] / hbd;
  1217. }
  1218. //
  1219. // line_to_current_position
  1220. // Move the planner to the current position from wherever it last moved
  1221. // (or from wherever it has been told it is located).
  1222. //
  1223. inline void line_to_current_position() {
  1224. planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate / 60, active_extruder);
  1225. }
  1226. inline void line_to_z(float zPosition) {
  1227. planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate / 60, active_extruder);
  1228. }
  1229. //
  1230. // line_to_destination
  1231. // Move the planner, not necessarily synced with current_position
  1232. //
  1233. inline void line_to_destination(float mm_m) {
  1234. planner.buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], mm_m / 60, active_extruder);
  1235. }
  1236. inline void line_to_destination() {
  1237. line_to_destination(feedrate);
  1238. }
  1239. /**
  1240. * sync_plan_position
  1241. * Set planner / stepper positions to the cartesian current_position.
  1242. * The stepper code translates these coordinates into step units.
  1243. * Allows translation between steps and units (mm) for cartesian & core robots
  1244. */
  1245. inline void sync_plan_position() {
  1246. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1247. if (DEBUGGING(LEVELING)) DEBUG_POS("sync_plan_position", current_position);
  1248. #endif
  1249. planner.set_position_mm(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1250. }
  1251. inline void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); }
  1252. inline void set_current_to_destination() { memcpy(current_position, destination, sizeof(current_position)); }
  1253. inline void set_destination_to_current() { memcpy(destination, current_position, sizeof(destination)); }
  1254. static void setup_for_endstop_move() {
  1255. saved_feedrate = feedrate;
  1256. saved_feedrate_multiplier = feedrate_multiplier;
  1257. feedrate_multiplier = 100;
  1258. refresh_cmd_timeout();
  1259. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1260. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("setup_for_endstop_move > endstops.enable()");
  1261. #endif
  1262. endstops.enable();
  1263. }
  1264. #if ENABLED(AUTO_BED_LEVELING_FEATURE)
  1265. #if ENABLED(DELTA)
  1266. /**
  1267. * Calculate delta, start a line, and set current_position to destination
  1268. */
  1269. void prepare_move_raw() {
  1270. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1271. if (DEBUGGING(LEVELING)) DEBUG_POS("prepare_move_raw", destination);
  1272. #endif
  1273. refresh_cmd_timeout();
  1274. calculate_delta(destination);
  1275. planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], (feedrate / 60) * (feedrate_multiplier / 100.0), active_extruder);
  1276. set_current_to_destination();
  1277. }
  1278. #endif
  1279. #if ENABLED(AUTO_BED_LEVELING_GRID)
  1280. #if DISABLED(DELTA)
  1281. static void set_bed_level_equation_lsq(double* plane_equation_coefficients) {
  1282. //planner.bed_level_matrix.debug("bed level before");
  1283. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1284. planner.bed_level_matrix.set_to_identity();
  1285. if (DEBUGGING(LEVELING)) {
  1286. vector_3 uncorrected_position = planner.adjusted_position();
  1287. DEBUG_POS(">>> set_bed_level_equation_lsq", uncorrected_position);
  1288. DEBUG_POS(">>> set_bed_level_equation_lsq", current_position);
  1289. }
  1290. #endif
  1291. vector_3 planeNormal = vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1);
  1292. planner.bed_level_matrix = matrix_3x3::create_look_at(planeNormal);
  1293. vector_3 corrected_position = planner.adjusted_position();
  1294. current_position[X_AXIS] = corrected_position.x;
  1295. current_position[Y_AXIS] = corrected_position.y;
  1296. current_position[Z_AXIS] = corrected_position.z;
  1297. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1298. if (DEBUGGING(LEVELING)) DEBUG_POS("<<< set_bed_level_equation_lsq", corrected_position);
  1299. #endif
  1300. sync_plan_position();
  1301. }
  1302. #endif // !DELTA
  1303. #else // !AUTO_BED_LEVELING_GRID
  1304. static void set_bed_level_equation_3pts(float z_at_pt_1, float z_at_pt_2, float z_at_pt_3) {
  1305. planner.bed_level_matrix.set_to_identity();
  1306. vector_3 pt1 = vector_3(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, z_at_pt_1);
  1307. vector_3 pt2 = vector_3(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, z_at_pt_2);
  1308. vector_3 pt3 = vector_3(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, z_at_pt_3);
  1309. vector_3 planeNormal = vector_3::cross(pt1 - pt2, pt3 - pt2).get_normal();
  1310. if (planeNormal.z < 0) {
  1311. planeNormal.x = -planeNormal.x;
  1312. planeNormal.y = -planeNormal.y;
  1313. planeNormal.z = -planeNormal.z;
  1314. }
  1315. planner.bed_level_matrix = matrix_3x3::create_look_at(planeNormal);
  1316. vector_3 corrected_position = planner.adjusted_position();
  1317. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1318. if (DEBUGGING(LEVELING)) {
  1319. vector_3 uncorrected_position = corrected_position;
  1320. DEBUG_POS("set_bed_level_equation_3pts", uncorrected_position);
  1321. }
  1322. #endif
  1323. current_position[X_AXIS] = corrected_position.x;
  1324. current_position[Y_AXIS] = corrected_position.y;
  1325. current_position[Z_AXIS] = corrected_position.z;
  1326. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1327. if (DEBUGGING(LEVELING)) DEBUG_POS("set_bed_level_equation_3pts", corrected_position);
  1328. #endif
  1329. sync_plan_position();
  1330. }
  1331. #endif // !AUTO_BED_LEVELING_GRID
  1332. static void run_z_probe() {
  1333. /**
  1334. * To prevent stepper_inactive_time from running out and
  1335. * EXTRUDER_RUNOUT_PREVENT from extruding
  1336. */
  1337. refresh_cmd_timeout();
  1338. #if ENABLED(DELTA)
  1339. float start_z = current_position[Z_AXIS];
  1340. long start_steps = stepper.position(Z_AXIS);
  1341. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1342. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("run_z_probe (DELTA) 1");
  1343. #endif
  1344. // move down slowly until you find the bed
  1345. feedrate = homing_feedrate[Z_AXIS] / 4;
  1346. destination[Z_AXIS] = -10;
  1347. prepare_move_raw(); // this will also set_current_to_destination
  1348. stepper.synchronize();
  1349. endstops.hit_on_purpose(); // clear endstop hit flags
  1350. /**
  1351. * We have to let the planner know where we are right now as it
  1352. * is not where we said to go.
  1353. */
  1354. long stop_steps = stepper.position(Z_AXIS);
  1355. float mm = start_z - float(start_steps - stop_steps) / planner.axis_steps_per_unit[Z_AXIS];
  1356. current_position[Z_AXIS] = mm;
  1357. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1358. if (DEBUGGING(LEVELING)) DEBUG_POS("run_z_probe (DELTA) 2", current_position);
  1359. #endif
  1360. sync_plan_position_delta();
  1361. #else // !DELTA
  1362. planner.bed_level_matrix.set_to_identity();
  1363. feedrate = homing_feedrate[Z_AXIS];
  1364. // Move down until the Z probe (or endstop?) is triggered
  1365. float zPosition = -(Z_MAX_LENGTH + 10);
  1366. line_to_z(zPosition);
  1367. stepper.synchronize();
  1368. // Tell the planner where we ended up - Get this from the stepper handler
  1369. zPosition = stepper.get_axis_position_mm(Z_AXIS);
  1370. planner.set_position_mm(
  1371. current_position[X_AXIS], current_position[Y_AXIS], zPosition,
  1372. current_position[E_AXIS]
  1373. );
  1374. // move up the retract distance
  1375. zPosition += home_bump_mm(Z_AXIS);
  1376. line_to_z(zPosition);
  1377. stepper.synchronize();
  1378. endstops.hit_on_purpose(); // clear endstop hit flags
  1379. // move back down slowly to find bed
  1380. set_homing_bump_feedrate(Z_AXIS);
  1381. zPosition -= home_bump_mm(Z_AXIS) * 2;
  1382. line_to_z(zPosition);
  1383. stepper.synchronize();
  1384. endstops.hit_on_purpose(); // clear endstop hit flags
  1385. // Get the current stepper position after bumping an endstop
  1386. current_position[Z_AXIS] = stepper.get_axis_position_mm(Z_AXIS);
  1387. sync_plan_position();
  1388. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1389. if (DEBUGGING(LEVELING)) DEBUG_POS("run_z_probe", current_position);
  1390. #endif
  1391. #endif // !DELTA
  1392. }
  1393. /**
  1394. * Plan a move to (X, Y, Z) and set the current_position
  1395. * The final current_position may not be the one that was requested
  1396. */
  1397. static void do_blocking_move_to(float x, float y, float z) {
  1398. float oldFeedRate = feedrate;
  1399. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1400. if (DEBUGGING(LEVELING)) print_xyz("do_blocking_move_to", x, y, z);
  1401. #endif
  1402. #if ENABLED(DELTA)
  1403. feedrate = XY_TRAVEL_SPEED;
  1404. destination[X_AXIS] = x;
  1405. destination[Y_AXIS] = y;
  1406. destination[Z_AXIS] = z;
  1407. if (x == current_position[X_AXIS] && y == current_position[Y_AXIS])
  1408. prepare_move_raw(); // this will also set_current_to_destination
  1409. else
  1410. prepare_move(); // this will also set_current_to_destination
  1411. stepper.synchronize();
  1412. #else
  1413. feedrate = homing_feedrate[Z_AXIS];
  1414. current_position[Z_AXIS] = z;
  1415. line_to_current_position();
  1416. stepper.synchronize();
  1417. feedrate = xy_travel_speed;
  1418. current_position[X_AXIS] = x;
  1419. current_position[Y_AXIS] = y;
  1420. line_to_current_position();
  1421. stepper.synchronize();
  1422. #endif
  1423. feedrate = oldFeedRate;
  1424. }
  1425. inline void do_blocking_move_to_xy(float x, float y) {
  1426. do_blocking_move_to(x, y, current_position[Z_AXIS]);
  1427. }
  1428. inline void do_blocking_move_to_x(float x) {
  1429. do_blocking_move_to(x, current_position[Y_AXIS], current_position[Z_AXIS]);
  1430. }
  1431. inline void do_blocking_move_to_z(float z) {
  1432. do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z);
  1433. }
  1434. inline void raise_z_after_probing() {
  1435. #if Z_RAISE_AFTER_PROBING > 0
  1436. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1437. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("raise_z_after_probing()");
  1438. #endif
  1439. do_blocking_move_to_z(current_position[Z_AXIS] + Z_RAISE_AFTER_PROBING);
  1440. #endif
  1441. }
  1442. static void clean_up_after_endstop_move() {
  1443. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1444. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("clean_up_after_endstop_move > ENDSTOPS_ONLY_FOR_HOMING > endstops.not_homing()");
  1445. #endif
  1446. endstops.not_homing();
  1447. feedrate = saved_feedrate;
  1448. feedrate_multiplier = saved_feedrate_multiplier;
  1449. refresh_cmd_timeout();
  1450. }
  1451. #if HAS_BED_PROBE
  1452. static void deploy_z_probe() {
  1453. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1454. if (DEBUGGING(LEVELING)) DEBUG_POS("deploy_z_probe", current_position);
  1455. #endif
  1456. if (endstops.z_probe_enabled) return;
  1457. #if ENABLED(HAS_SERVO_ENDSTOPS)
  1458. // Engage Z Servo endstop if enabled
  1459. if (servo_endstop_id[Z_AXIS] >= 0) servo[servo_endstop_id[Z_AXIS]].move(servo_endstop_angle[Z_AXIS][0]);
  1460. #elif ENABLED(Z_PROBE_ALLEN_KEY)
  1461. feedrate = Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE;
  1462. // If endstop is already false, the Z probe is deployed
  1463. #if ENABLED(Z_MIN_PROBE_ENDSTOP)
  1464. bool z_probe_endstop = (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING);
  1465. if (z_probe_endstop)
  1466. #else
  1467. bool z_min_endstop = (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
  1468. if (z_min_endstop)
  1469. #endif
  1470. {
  1471. // Move to the start position to initiate deployment
  1472. destination[X_AXIS] = Z_PROBE_ALLEN_KEY_DEPLOY_1_X;
  1473. destination[Y_AXIS] = Z_PROBE_ALLEN_KEY_DEPLOY_1_Y;
  1474. destination[Z_AXIS] = Z_PROBE_ALLEN_KEY_DEPLOY_1_Z;
  1475. prepare_move_raw(); // this will also set_current_to_destination
  1476. // Move to engage deployment
  1477. if (Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE != Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE)
  1478. feedrate = Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE;
  1479. if (Z_PROBE_ALLEN_KEY_DEPLOY_2_X != Z_PROBE_ALLEN_KEY_DEPLOY_1_X)
  1480. destination[X_AXIS] = Z_PROBE_ALLEN_KEY_DEPLOY_2_X;
  1481. if (Z_PROBE_ALLEN_KEY_DEPLOY_2_Y != Z_PROBE_ALLEN_KEY_DEPLOY_1_Y)
  1482. destination[Y_AXIS] = Z_PROBE_ALLEN_KEY_DEPLOY_2_Y;
  1483. if (Z_PROBE_ALLEN_KEY_DEPLOY_2_Z != Z_PROBE_ALLEN_KEY_DEPLOY_1_Z)
  1484. destination[Z_AXIS] = Z_PROBE_ALLEN_KEY_DEPLOY_2_Z;
  1485. prepare_move_raw();
  1486. #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_3_X
  1487. if (Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE != Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE)
  1488. feedrate = Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE;
  1489. // Move to trigger deployment
  1490. if (Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE != Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE)
  1491. feedrate = Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE;
  1492. if (Z_PROBE_ALLEN_KEY_DEPLOY_3_X != Z_PROBE_ALLEN_KEY_DEPLOY_2_X)
  1493. destination[X_AXIS] = Z_PROBE_ALLEN_KEY_DEPLOY_3_X;
  1494. if (Z_PROBE_ALLEN_KEY_DEPLOY_3_Y != Z_PROBE_ALLEN_KEY_DEPLOY_2_Y)
  1495. destination[Y_AXIS] = Z_PROBE_ALLEN_KEY_DEPLOY_3_Y;
  1496. if (Z_PROBE_ALLEN_KEY_DEPLOY_3_Z != Z_PROBE_ALLEN_KEY_DEPLOY_2_Z)
  1497. destination[Z_AXIS] = Z_PROBE_ALLEN_KEY_DEPLOY_3_Z;
  1498. prepare_move_raw();
  1499. #endif
  1500. }
  1501. // Partially Home X,Y for safety
  1502. destination[X_AXIS] = destination[X_AXIS] * 0.75;
  1503. destination[Y_AXIS] = destination[Y_AXIS] * 0.75;
  1504. prepare_move_raw(); // this will also set_current_to_destination
  1505. stepper.synchronize();
  1506. #if ENABLED(Z_MIN_PROBE_ENDSTOP)
  1507. z_probe_endstop = (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING);
  1508. if (z_probe_endstop)
  1509. #else
  1510. z_min_endstop = (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
  1511. if (z_min_endstop)
  1512. #endif
  1513. {
  1514. if (IsRunning()) {
  1515. SERIAL_ERROR_START;
  1516. SERIAL_ERRORLNPGM("Z-Probe failed to engage!");
  1517. LCD_ALERTMESSAGEPGM("Err: ZPROBE");
  1518. }
  1519. stop();
  1520. }
  1521. #endif // Z_PROBE_ALLEN_KEY
  1522. #if ENABLED(FIX_MOUNTED_PROBE)
  1523. // Noting to be done. Just set endstops.z_probe_enabled
  1524. #endif
  1525. endstops.enable_z_probe();
  1526. }
  1527. static void stow_z_probe(bool doRaise = true) {
  1528. #if !(ENABLED(HAS_SERVO_ENDSTOPS) && (Z_RAISE_AFTER_PROBING > 0))
  1529. UNUSED(doRaise);
  1530. #endif
  1531. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1532. if (DEBUGGING(LEVELING)) DEBUG_POS("stow_z_probe", current_position);
  1533. #endif
  1534. if (!endstops.z_probe_enabled) return;
  1535. #if ENABLED(HAS_SERVO_ENDSTOPS)
  1536. // Retract Z Servo endstop if enabled
  1537. if (servo_endstop_id[Z_AXIS] >= 0) {
  1538. #if Z_RAISE_AFTER_PROBING > 0
  1539. if (doRaise) {
  1540. raise_z_after_probing(); // this also updates current_position
  1541. stepper.synchronize();
  1542. }
  1543. #endif
  1544. // Change the Z servo angle
  1545. servo[servo_endstop_id[Z_AXIS]].move(servo_endstop_angle[Z_AXIS][1]);
  1546. }
  1547. #elif ENABLED(Z_PROBE_ALLEN_KEY)
  1548. // Move up for safety
  1549. feedrate = Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE;
  1550. #if Z_RAISE_AFTER_PROBING > 0
  1551. destination[Z_AXIS] = current_position[Z_AXIS] + Z_RAISE_AFTER_PROBING;
  1552. prepare_move_raw(); // this will also set_current_to_destination
  1553. #endif
  1554. // Move to the start position to initiate retraction
  1555. destination[X_AXIS] = Z_PROBE_ALLEN_KEY_STOW_1_X;
  1556. destination[Y_AXIS] = Z_PROBE_ALLEN_KEY_STOW_1_Y;
  1557. destination[Z_AXIS] = Z_PROBE_ALLEN_KEY_STOW_1_Z;
  1558. prepare_move_raw();
  1559. // Move the nozzle down to push the Z probe into retracted position
  1560. if (Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE != Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE)
  1561. feedrate = Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE;
  1562. if (Z_PROBE_ALLEN_KEY_STOW_2_X != Z_PROBE_ALLEN_KEY_STOW_1_X)
  1563. destination[X_AXIS] = Z_PROBE_ALLEN_KEY_STOW_2_X;
  1564. if (Z_PROBE_ALLEN_KEY_STOW_2_Y != Z_PROBE_ALLEN_KEY_STOW_1_Y)
  1565. destination[Y_AXIS] = Z_PROBE_ALLEN_KEY_STOW_2_Y;
  1566. destination[Z_AXIS] = Z_PROBE_ALLEN_KEY_STOW_2_Z;
  1567. prepare_move_raw();
  1568. // Move up for safety
  1569. if (Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE != Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE)
  1570. feedrate = Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE;
  1571. if (Z_PROBE_ALLEN_KEY_STOW_3_X != Z_PROBE_ALLEN_KEY_STOW_2_X)
  1572. destination[X_AXIS] = Z_PROBE_ALLEN_KEY_STOW_3_X;
  1573. if (Z_PROBE_ALLEN_KEY_STOW_3_Y != Z_PROBE_ALLEN_KEY_STOW_2_Y)
  1574. destination[Y_AXIS] = Z_PROBE_ALLEN_KEY_STOW_3_Y;
  1575. destination[Z_AXIS] = Z_PROBE_ALLEN_KEY_STOW_3_Z;
  1576. prepare_move_raw();
  1577. // Home XY for safety
  1578. feedrate = homing_feedrate[X_AXIS] / 2;
  1579. destination[X_AXIS] = 0;
  1580. destination[Y_AXIS] = 0;
  1581. prepare_move_raw(); // this will also set_current_to_destination
  1582. stepper.synchronize();
  1583. #if ENABLED(Z_MIN_PROBE_ENDSTOP)
  1584. bool z_probe_endstop = (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING);
  1585. if (!z_probe_endstop)
  1586. #else
  1587. bool z_min_endstop = (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
  1588. if (!z_min_endstop)
  1589. #endif
  1590. {
  1591. if (IsRunning()) {
  1592. SERIAL_ERROR_START;
  1593. SERIAL_ERRORLNPGM("Z-Probe failed to retract!");
  1594. LCD_ALERTMESSAGEPGM("Err: ZPROBE");
  1595. }
  1596. stop();
  1597. }
  1598. #endif // Z_PROBE_ALLEN_KEY
  1599. #if ENABLED(FIX_MOUNTED_PROBE)
  1600. // Nothing to do here. Just clear endstops.z_probe_enabled
  1601. #endif
  1602. endstops.enable_z_probe(false);
  1603. }
  1604. #endif // HAS_BED_PROBE
  1605. enum ProbeAction {
  1606. ProbeStay = 0,
  1607. ProbeDeploy = _BV(0),
  1608. ProbeStow = _BV(1),
  1609. ProbeDeployAndStow = (ProbeDeploy | ProbeStow)
  1610. };
  1611. // Probe bed height at position (x,y), returns the measured z value
  1612. static float probe_pt(float x, float y, float z_before, ProbeAction probe_action = ProbeDeployAndStow, int verbose_level = 1) {
  1613. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1614. if (DEBUGGING(LEVELING)) {
  1615. SERIAL_ECHOLNPGM("probe_pt >>>");
  1616. SERIAL_ECHOPAIR("> ProbeAction:", probe_action);
  1617. SERIAL_EOL;
  1618. DEBUG_POS("", current_position);
  1619. }
  1620. #endif
  1621. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1622. if (DEBUGGING(LEVELING)) {
  1623. SERIAL_ECHOPAIR("Z Raise to z_before ", z_before);
  1624. SERIAL_EOL;
  1625. SERIAL_ECHOPAIR("> do_blocking_move_to_z ", z_before);
  1626. SERIAL_EOL;
  1627. }
  1628. #endif
  1629. // Move Z up to the z_before height, then move the Z probe to the given XY
  1630. do_blocking_move_to_z(z_before); // this also updates current_position
  1631. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1632. if (DEBUGGING(LEVELING)) {
  1633. SERIAL_ECHOPAIR("> do_blocking_move_to_xy ", x - (X_PROBE_OFFSET_FROM_EXTRUDER));
  1634. SERIAL_ECHOPAIR(", ", y - (Y_PROBE_OFFSET_FROM_EXTRUDER));
  1635. SERIAL_EOL;
  1636. }
  1637. #endif
  1638. // this also updates current_position
  1639. do_blocking_move_to_xy(x - (X_PROBE_OFFSET_FROM_EXTRUDER), y - (Y_PROBE_OFFSET_FROM_EXTRUDER));
  1640. #if DISABLED(Z_PROBE_SLED) && DISABLED(Z_PROBE_ALLEN_KEY)
  1641. if (probe_action & ProbeDeploy) {
  1642. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1643. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> ProbeDeploy");
  1644. #endif
  1645. deploy_z_probe();
  1646. }
  1647. #endif
  1648. run_z_probe();
  1649. float measured_z = current_position[Z_AXIS];
  1650. #if DISABLED(Z_PROBE_SLED) && DISABLED(Z_PROBE_ALLEN_KEY)
  1651. if (probe_action & ProbeStow) {
  1652. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1653. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> ProbeStow (stow_z_probe will do Z Raise)");
  1654. #endif
  1655. stow_z_probe();
  1656. }
  1657. #endif
  1658. if (verbose_level > 2) {
  1659. SERIAL_PROTOCOLPGM("Bed X: ");
  1660. SERIAL_PROTOCOL_F(x, 3);
  1661. SERIAL_PROTOCOLPGM(" Y: ");
  1662. SERIAL_PROTOCOL_F(y, 3);
  1663. SERIAL_PROTOCOLPGM(" Z: ");
  1664. SERIAL_PROTOCOL_F(measured_z, 3);
  1665. SERIAL_EOL;
  1666. }
  1667. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1668. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< probe_pt");
  1669. #endif
  1670. return measured_z;
  1671. }
  1672. #if ENABLED(DELTA)
  1673. /**
  1674. * All DELTA leveling in the Marlin uses NONLINEAR_BED_LEVELING
  1675. */
  1676. static void extrapolate_one_point(int x, int y, int xdir, int ydir) {
  1677. if (bed_level[x][y] != 0.0) {
  1678. return; // Don't overwrite good values.
  1679. }
  1680. float a = 2 * bed_level[x + xdir][y] - bed_level[x + xdir * 2][y]; // Left to right.
  1681. float b = 2 * bed_level[x][y + ydir] - bed_level[x][y + ydir * 2]; // Front to back.
  1682. float c = 2 * bed_level[x + xdir][y + ydir] - bed_level[x + xdir * 2][y + ydir * 2]; // Diagonal.
  1683. float median = c; // Median is robust (ignores outliers).
  1684. if (a < b) {
  1685. if (b < c) median = b;
  1686. if (c < a) median = a;
  1687. }
  1688. else { // b <= a
  1689. if (c < b) median = b;
  1690. if (a < c) median = a;
  1691. }
  1692. bed_level[x][y] = median;
  1693. }
  1694. /**
  1695. * Fill in the unprobed points (corners of circular print surface)
  1696. * using linear extrapolation, away from the center.
  1697. */
  1698. static void extrapolate_unprobed_bed_level() {
  1699. int half = (AUTO_BED_LEVELING_GRID_POINTS - 1) / 2;
  1700. for (int y = 0; y <= half; y++) {
  1701. for (int x = 0; x <= half; x++) {
  1702. if (x + y < 3) continue;
  1703. extrapolate_one_point(half - x, half - y, x > 1 ? +1 : 0, y > 1 ? +1 : 0);
  1704. extrapolate_one_point(half + x, half - y, x > 1 ? -1 : 0, y > 1 ? +1 : 0);
  1705. extrapolate_one_point(half - x, half + y, x > 1 ? +1 : 0, y > 1 ? -1 : 0);
  1706. extrapolate_one_point(half + x, half + y, x > 1 ? -1 : 0, y > 1 ? -1 : 0);
  1707. }
  1708. }
  1709. }
  1710. /**
  1711. * Print calibration results for plotting or manual frame adjustment.
  1712. */
  1713. static void print_bed_level() {
  1714. for (int y = 0; y < AUTO_BED_LEVELING_GRID_POINTS; y++) {
  1715. for (int x = 0; x < AUTO_BED_LEVELING_GRID_POINTS; x++) {
  1716. SERIAL_PROTOCOL_F(bed_level[x][y], 2);
  1717. SERIAL_PROTOCOLCHAR(' ');
  1718. }
  1719. SERIAL_EOL;
  1720. }
  1721. }
  1722. /**
  1723. * Reset calibration results to zero.
  1724. */
  1725. void reset_bed_level() {
  1726. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1727. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("reset_bed_level");
  1728. #endif
  1729. for (int y = 0; y < AUTO_BED_LEVELING_GRID_POINTS; y++) {
  1730. for (int x = 0; x < AUTO_BED_LEVELING_GRID_POINTS; x++) {
  1731. bed_level[x][y] = 0.0;
  1732. }
  1733. }
  1734. }
  1735. #endif // DELTA
  1736. #if ENABLED(HAS_SERVO_ENDSTOPS) && DISABLED(Z_PROBE_SLED)
  1737. void raise_z_for_servo() {
  1738. float zpos = current_position[Z_AXIS], z_dest = Z_RAISE_BEFORE_PROBING;
  1739. /**
  1740. * The zprobe_zoffset is negative any switch below the nozzle, so
  1741. * multiply by Z_HOME_DIR (-1) to move enough away from bed for the probe
  1742. */
  1743. z_dest += axis_homed[Z_AXIS] ? zprobe_zoffset * Z_HOME_DIR : zpos;
  1744. if (zpos < z_dest) do_blocking_move_to_z(z_dest); // also updates current_position
  1745. }
  1746. #endif
  1747. #endif // AUTO_BED_LEVELING_FEATURE
  1748. #if ENABLED(Z_PROBE_SLED) || ENABLED(Z_SAFE_HOMING) || ENABLED(AUTO_BED_LEVELING_FEATURE)
  1749. static void axis_unhomed_error(bool xyz=false) {
  1750. if (xyz) {
  1751. LCD_MESSAGEPGM(MSG_XYZ_UNHOMED);
  1752. SERIAL_ECHO_START;
  1753. SERIAL_ECHOLNPGM(MSG_XYZ_UNHOMED);
  1754. }
  1755. else {
  1756. LCD_MESSAGEPGM(MSG_YX_UNHOMED);
  1757. SERIAL_ECHO_START;
  1758. SERIAL_ECHOLNPGM(MSG_YX_UNHOMED);
  1759. }
  1760. }
  1761. #endif
  1762. #if ENABLED(Z_PROBE_SLED)
  1763. #ifndef SLED_DOCKING_OFFSET
  1764. #define SLED_DOCKING_OFFSET 0
  1765. #endif
  1766. /**
  1767. * Method to dock/undock a sled designed by Charles Bell.
  1768. *
  1769. * dock[in] If true, move to MAX_X and engage the electromagnet
  1770. * offset[in] The additional distance to move to adjust docking location
  1771. */
  1772. static void dock_sled(bool dock, int offset = 0) {
  1773. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1774. if (DEBUGGING(LEVELING)) {
  1775. SERIAL_ECHOPAIR("dock_sled(", dock);
  1776. SERIAL_ECHOLNPGM(")");
  1777. }
  1778. #endif
  1779. if (!axis_homed[X_AXIS] || !axis_homed[Y_AXIS] || !axis_homed[Z_AXIS]) {
  1780. axis_unhomed_error(true);
  1781. return;
  1782. }
  1783. if (endstops.z_probe_enabled == !dock) return; // already docked/undocked?
  1784. float oldXpos = current_position[X_AXIS]; // save x position
  1785. if (dock) {
  1786. raise_z_after_probing(); // raise Z
  1787. // Dock sled a bit closer to ensure proper capturing
  1788. do_blocking_move_to_x(X_MAX_POS + SLED_DOCKING_OFFSET + offset - 1);
  1789. digitalWrite(SLED_PIN, LOW); // turn off magnet
  1790. }
  1791. else {
  1792. float z_loc = current_position[Z_AXIS];
  1793. if (z_loc < Z_RAISE_BEFORE_PROBING + 5) z_loc = Z_RAISE_BEFORE_PROBING;
  1794. do_blocking_move_to(X_MAX_POS + SLED_DOCKING_OFFSET + offset, current_position[Y_AXIS], z_loc); // this also updates current_position
  1795. digitalWrite(SLED_PIN, HIGH); // turn on magnet
  1796. }
  1797. do_blocking_move_to_x(oldXpos); // return to position before docking
  1798. endstops.enable_z_probe(!dock); // logically disable docked probe
  1799. }
  1800. #endif // Z_PROBE_SLED
  1801. /**
  1802. * Home an individual axis
  1803. */
  1804. #define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS)
  1805. static void homeaxis(AxisEnum axis) {
  1806. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1807. if (DEBUGGING(LEVELING)) {
  1808. SERIAL_ECHOPAIR(">>> homeaxis(", axis);
  1809. SERIAL_ECHOLNPGM(")");
  1810. }
  1811. #endif
  1812. #define HOMEAXIS_DO(LETTER) \
  1813. ((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1))
  1814. if (axis == X_AXIS ? HOMEAXIS_DO(X) : axis == Y_AXIS ? HOMEAXIS_DO(Y) : axis == Z_AXIS ? HOMEAXIS_DO(Z) : 0) {
  1815. int axis_home_dir =
  1816. #if ENABLED(DUAL_X_CARRIAGE)
  1817. (axis == X_AXIS) ? x_home_dir(active_extruder) :
  1818. #endif
  1819. home_dir(axis);
  1820. // Set the axis position as setup for the move
  1821. current_position[axis] = 0;
  1822. sync_plan_position();
  1823. #if ENABLED(Z_PROBE_SLED)
  1824. #define _Z_SERVO_TEST (axis != Z_AXIS) // already deployed Z
  1825. #define _Z_SERVO_SUBTEST false // Z will never be invoked
  1826. #define _Z_DEPLOY (dock_sled(false))
  1827. #define _Z_STOW (dock_sled(true))
  1828. #elif SERVO_LEVELING || ENABLED(FIX_MOUNTED_PROBE)
  1829. #define _Z_SERVO_TEST (axis != Z_AXIS) // already deployed Z
  1830. #define _Z_SERVO_SUBTEST false // Z will never be invoked
  1831. #define _Z_DEPLOY (deploy_z_probe())
  1832. #define _Z_STOW (stow_z_probe())
  1833. #elif ENABLED(HAS_SERVO_ENDSTOPS)
  1834. #define _Z_SERVO_TEST true // Z not deployed yet
  1835. #define _Z_SERVO_SUBTEST (axis == Z_AXIS) // Z is a probe
  1836. #endif
  1837. // If there's a Z probe that needs deployment...
  1838. #if ENABLED(Z_PROBE_SLED) || SERVO_LEVELING || ENABLED(FIX_MOUNTED_PROBE)
  1839. // ...and homing Z towards the bed? Deploy it.
  1840. if (axis == Z_AXIS && axis_home_dir < 0) {
  1841. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1842. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> SERVO_LEVELING > " STRINGIFY(_Z_DEPLOY));
  1843. #endif
  1844. _Z_DEPLOY;
  1845. }
  1846. #endif
  1847. #if ENABLED(HAS_SERVO_ENDSTOPS)
  1848. // Engage an X, Y (or Z) Servo endstop if enabled
  1849. if (_Z_SERVO_TEST && servo_endstop_id[axis] >= 0) {
  1850. servo[servo_endstop_id[axis]].move(servo_endstop_angle[axis][0]);
  1851. if (_Z_SERVO_SUBTEST) endstops.z_probe_enabled = true;
  1852. }
  1853. #endif
  1854. // Set a flag for Z motor locking
  1855. #if ENABLED(Z_DUAL_ENDSTOPS)
  1856. if (axis == Z_AXIS) stepper.set_homing_flag(true);
  1857. #endif
  1858. // Move towards the endstop until an endstop is triggered
  1859. destination[axis] = 1.5 * max_length(axis) * axis_home_dir;
  1860. feedrate = homing_feedrate[axis];
  1861. line_to_destination();
  1862. stepper.synchronize();
  1863. // Set the axis position as setup for the move
  1864. current_position[axis] = 0;
  1865. sync_plan_position();
  1866. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1867. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> endstops.enable(false)");
  1868. #endif
  1869. endstops.enable(false); // Disable endstops while moving away
  1870. // Move away from the endstop by the axis HOME_BUMP_MM
  1871. destination[axis] = -home_bump_mm(axis) * axis_home_dir;
  1872. line_to_destination();
  1873. stepper.synchronize();
  1874. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1875. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> endstops.enable(true)");
  1876. #endif
  1877. endstops.enable(true); // Enable endstops for next homing move
  1878. // Slow down the feedrate for the next move
  1879. set_homing_bump_feedrate(axis);
  1880. // Move slowly towards the endstop until triggered
  1881. destination[axis] = 2 * home_bump_mm(axis) * axis_home_dir;
  1882. line_to_destination();
  1883. stepper.synchronize();
  1884. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1885. if (DEBUGGING(LEVELING)) DEBUG_POS("> TRIGGER ENDSTOP", current_position);
  1886. #endif
  1887. #if ENABLED(Z_DUAL_ENDSTOPS)
  1888. if (axis == Z_AXIS) {
  1889. float adj = fabs(z_endstop_adj);
  1890. bool lockZ1;
  1891. if (axis_home_dir > 0) {
  1892. adj = -adj;
  1893. lockZ1 = (z_endstop_adj > 0);
  1894. }
  1895. else
  1896. lockZ1 = (z_endstop_adj < 0);
  1897. if (lockZ1) stepper.set_z_lock(true); else stepper.set_z2_lock(true);
  1898. sync_plan_position();
  1899. // Move to the adjusted endstop height
  1900. feedrate = homing_feedrate[axis];
  1901. destination[Z_AXIS] = adj;
  1902. line_to_destination();
  1903. stepper.synchronize();
  1904. if (lockZ1) stepper.set_z_lock(false); else stepper.set_z2_lock(false);
  1905. stepper.set_homing_flag(false);
  1906. } // Z_AXIS
  1907. #endif
  1908. #if ENABLED(DELTA)
  1909. // retrace by the amount specified in endstop_adj
  1910. if (endstop_adj[axis] * axis_home_dir < 0) {
  1911. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1912. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> endstops.enable(false)");
  1913. #endif
  1914. endstops.enable(false); // Disable endstops while moving away
  1915. sync_plan_position();
  1916. destination[axis] = endstop_adj[axis];
  1917. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1918. if (DEBUGGING(LEVELING)) {
  1919. SERIAL_ECHOPAIR("> endstop_adj = ", endstop_adj[axis]);
  1920. DEBUG_POS("", destination);
  1921. }
  1922. #endif
  1923. line_to_destination();
  1924. stepper.synchronize();
  1925. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1926. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> endstops.enable(true)");
  1927. #endif
  1928. endstops.enable(true); // Enable endstops for next homing move
  1929. }
  1930. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1931. else {
  1932. if (DEBUGGING(LEVELING)) {
  1933. SERIAL_ECHOPAIR("> endstop_adj * axis_home_dir = ", endstop_adj[axis] * axis_home_dir);
  1934. SERIAL_EOL;
  1935. }
  1936. }
  1937. #endif
  1938. #endif
  1939. // Set the axis position to its home position (plus home offsets)
  1940. set_axis_is_at_home(axis);
  1941. sync_plan_position();
  1942. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1943. if (DEBUGGING(LEVELING)) DEBUG_POS("> AFTER set_axis_is_at_home", current_position);
  1944. #endif
  1945. destination[axis] = current_position[axis];
  1946. feedrate = 0.0;
  1947. endstops.hit_on_purpose(); // clear endstop hit flags
  1948. axis_known_position[axis] = true;
  1949. axis_homed[axis] = true;
  1950. // Put away the Z probe with a function
  1951. #if ENABLED(Z_PROBE_SLED) || SERVO_LEVELING || ENABLED(FIX_MOUNTED_PROBE)
  1952. if (axis == Z_AXIS && axis_home_dir < 0) {
  1953. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1954. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> SERVO_LEVELING > " STRINGIFY(_Z_STOW));
  1955. #endif
  1956. _Z_STOW;
  1957. }
  1958. #endif
  1959. // Retract X, Y (or Z) Servo endstop if enabled
  1960. #if ENABLED(HAS_SERVO_ENDSTOPS)
  1961. if (_Z_SERVO_TEST && servo_endstop_id[axis] >= 0) {
  1962. // Raise the servo probe before stow outside ABL context.
  1963. // This is a workaround to allow use of a Servo Probe without
  1964. // ABL until more global probe handling is implemented.
  1965. #if Z_RAISE_AFTER_PROBING > 0
  1966. if (axis == Z_AXIS) {
  1967. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1968. if (DEBUGGING(LEVELING)) SERIAL_ECHOPAIR("Raise Z (after) by ", Z_RAISE_AFTER_PROBING);
  1969. #endif
  1970. current_position[Z_AXIS] = Z_RAISE_AFTER_PROBING;
  1971. feedrate = homing_feedrate[Z_AXIS];
  1972. line_to_current_position();
  1973. stepper.synchronize();
  1974. }
  1975. #endif
  1976. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1977. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> SERVO_ENDSTOPS > Stow with servo.move()");
  1978. #endif
  1979. servo[servo_endstop_id[axis]].move(servo_endstop_angle[axis][1]);
  1980. if (_Z_SERVO_SUBTEST) endstops.enable_z_probe(false);
  1981. }
  1982. #endif // HAS_SERVO_ENDSTOPS
  1983. }
  1984. #if ENABLED(DEBUG_LEVELING_FEATURE)
  1985. if (DEBUGGING(LEVELING)) {
  1986. SERIAL_ECHOPAIR("<<< homeaxis(", axis);
  1987. SERIAL_ECHOLNPGM(")");
  1988. }
  1989. #endif
  1990. }
  1991. #if ENABLED(FWRETRACT)
  1992. void retract(bool retracting, bool swapping = false) {
  1993. if (retracting == retracted[active_extruder]) return;
  1994. float oldFeedrate = feedrate;
  1995. set_destination_to_current();
  1996. if (retracting) {
  1997. feedrate = retract_feedrate * 60;
  1998. current_position[E_AXIS] += (swapping ? retract_length_swap : retract_length) / volumetric_multiplier[active_extruder];
  1999. sync_plan_position_e();
  2000. prepare_move();
  2001. if (retract_zlift > 0.01) {
  2002. current_position[Z_AXIS] -= retract_zlift;
  2003. #if ENABLED(DELTA)
  2004. sync_plan_position_delta();
  2005. #else
  2006. sync_plan_position();
  2007. #endif
  2008. prepare_move();
  2009. }
  2010. }
  2011. else {
  2012. if (retract_zlift > 0.01) {
  2013. current_position[Z_AXIS] += retract_zlift;
  2014. #if ENABLED(DELTA)
  2015. sync_plan_position_delta();
  2016. #else
  2017. sync_plan_position();
  2018. #endif
  2019. }
  2020. feedrate = retract_recover_feedrate * 60;
  2021. float move_e = swapping ? retract_length_swap + retract_recover_length_swap : retract_length + retract_recover_length;
  2022. current_position[E_AXIS] -= move_e / volumetric_multiplier[active_extruder];
  2023. sync_plan_position_e();
  2024. prepare_move();
  2025. }
  2026. feedrate = oldFeedrate;
  2027. retracted[active_extruder] = retracting;
  2028. } // retract()
  2029. #endif // FWRETRACT
  2030. /**
  2031. * ***************************************************************************
  2032. * ***************************** G-CODE HANDLING *****************************
  2033. * ***************************************************************************
  2034. */
  2035. /**
  2036. * Set XYZE destination and feedrate from the current GCode command
  2037. *
  2038. * - Set destination from included axis codes
  2039. * - Set to current for missing axis codes
  2040. * - Set the feedrate, if included
  2041. */
  2042. void gcode_get_destination() {
  2043. for (int i = 0; i < NUM_AXIS; i++) {
  2044. if (code_seen(axis_codes[i]))
  2045. destination[i] = code_value() + (axis_relative_modes[i] || relative_mode ? current_position[i] : 0);
  2046. else
  2047. destination[i] = current_position[i];
  2048. }
  2049. if (code_seen('F')) {
  2050. float next_feedrate = code_value();
  2051. if (next_feedrate > 0.0) feedrate = next_feedrate;
  2052. }
  2053. }
  2054. void unknown_command_error() {
  2055. SERIAL_ECHO_START;
  2056. SERIAL_ECHOPGM(MSG_UNKNOWN_COMMAND);
  2057. SERIAL_ECHO(current_command);
  2058. SERIAL_ECHOPGM("\"\n");
  2059. }
  2060. #if ENABLED(HOST_KEEPALIVE_FEATURE)
  2061. /**
  2062. * Output a "busy" message at regular intervals
  2063. * while the machine is not accepting commands.
  2064. */
  2065. void host_keepalive() {
  2066. millis_t ms = millis();
  2067. if (host_keepalive_interval && busy_state != NOT_BUSY) {
  2068. if (PENDING(ms, next_busy_signal_ms)) return;
  2069. switch (busy_state) {
  2070. case IN_HANDLER:
  2071. case IN_PROCESS:
  2072. SERIAL_ECHO_START;
  2073. SERIAL_ECHOLNPGM(MSG_BUSY_PROCESSING);
  2074. break;
  2075. case PAUSED_FOR_USER:
  2076. SERIAL_ECHO_START;
  2077. SERIAL_ECHOLNPGM(MSG_BUSY_PAUSED_FOR_USER);
  2078. break;
  2079. case PAUSED_FOR_INPUT:
  2080. SERIAL_ECHO_START;
  2081. SERIAL_ECHOLNPGM(MSG_BUSY_PAUSED_FOR_INPUT);
  2082. break;
  2083. default:
  2084. break;
  2085. }
  2086. }
  2087. next_busy_signal_ms = ms + host_keepalive_interval * 1000UL;
  2088. }
  2089. #endif //HOST_KEEPALIVE_FEATURE
  2090. /**
  2091. * G0, G1: Coordinated movement of X Y Z E axes
  2092. */
  2093. inline void gcode_G0_G1() {
  2094. if (IsRunning()) {
  2095. gcode_get_destination(); // For X Y Z E F
  2096. #if ENABLED(FWRETRACT)
  2097. if (autoretract_enabled && !(code_seen('X') || code_seen('Y') || code_seen('Z')) && code_seen('E')) {
  2098. float echange = destination[E_AXIS] - current_position[E_AXIS];
  2099. // Is this move an attempt to retract or recover?
  2100. if ((echange < -MIN_RETRACT && !retracted[active_extruder]) || (echange > MIN_RETRACT && retracted[active_extruder])) {
  2101. current_position[E_AXIS] = destination[E_AXIS]; // hide the slicer-generated retract/recover from calculations
  2102. sync_plan_position_e(); // AND from the planner
  2103. retract(!retracted[active_extruder]);
  2104. return;
  2105. }
  2106. }
  2107. #endif //FWRETRACT
  2108. prepare_move();
  2109. }
  2110. }
  2111. /**
  2112. * G2: Clockwise Arc
  2113. * G3: Counterclockwise Arc
  2114. */
  2115. #if ENABLED(ARC_SUPPORT)
  2116. inline void gcode_G2_G3(bool clockwise) {
  2117. if (IsRunning()) {
  2118. #if ENABLED(SF_ARC_FIX)
  2119. bool relative_mode_backup = relative_mode;
  2120. relative_mode = true;
  2121. #endif
  2122. gcode_get_destination();
  2123. #if ENABLED(SF_ARC_FIX)
  2124. relative_mode = relative_mode_backup;
  2125. #endif
  2126. // Center of arc as offset from current_position
  2127. float arc_offset[2] = {
  2128. code_seen('I') ? code_value() : 0,
  2129. code_seen('J') ? code_value() : 0
  2130. };
  2131. // Send an arc to the planner
  2132. plan_arc(destination, arc_offset, clockwise);
  2133. refresh_cmd_timeout();
  2134. }
  2135. }
  2136. #endif
  2137. /**
  2138. * G4: Dwell S<seconds> or P<milliseconds>
  2139. */
  2140. inline void gcode_G4() {
  2141. millis_t codenum = 0;
  2142. if (code_seen('P')) codenum = code_value_long(); // milliseconds to wait
  2143. if (code_seen('S')) codenum = code_value() * 1000UL; // seconds to wait
  2144. stepper.synchronize();
  2145. refresh_cmd_timeout();
  2146. codenum += previous_cmd_ms; // keep track of when we started waiting
  2147. if (!lcd_hasstatus()) LCD_MESSAGEPGM(MSG_DWELL);
  2148. while (PENDING(millis(), codenum)) idle();
  2149. }
  2150. #if ENABLED(BEZIER_CURVE_SUPPORT)
  2151. /**
  2152. * Parameters interpreted according to:
  2153. * http://linuxcnc.org/docs/2.6/html/gcode/gcode.html#sec:G5-Cubic-Spline
  2154. * However I, J omission is not supported at this point; all
  2155. * parameters can be omitted and default to zero.
  2156. */
  2157. /**
  2158. * G5: Cubic B-spline
  2159. */
  2160. inline void gcode_G5() {
  2161. if (IsRunning()) {
  2162. gcode_get_destination();
  2163. float offset[] = {
  2164. code_seen('I') ? code_value() : 0.0,
  2165. code_seen('J') ? code_value() : 0.0,
  2166. code_seen('P') ? code_value() : 0.0,
  2167. code_seen('Q') ? code_value() : 0.0
  2168. };
  2169. plan_cubic_move(offset);
  2170. }
  2171. }
  2172. #endif // BEZIER_CURVE_SUPPORT
  2173. #if ENABLED(FWRETRACT)
  2174. /**
  2175. * G10 - Retract filament according to settings of M207
  2176. * G11 - Recover filament according to settings of M208
  2177. */
  2178. inline void gcode_G10_G11(bool doRetract=false) {
  2179. #if EXTRUDERS > 1
  2180. if (doRetract) {
  2181. retracted_swap[active_extruder] = (code_seen('S') && code_value_short() == 1); // checks for swap retract argument
  2182. }
  2183. #endif
  2184. retract(doRetract
  2185. #if EXTRUDERS > 1
  2186. , retracted_swap[active_extruder]
  2187. #endif
  2188. );
  2189. }
  2190. #endif //FWRETRACT
  2191. /**
  2192. * G28: Home all axes according to settings
  2193. *
  2194. * Parameters
  2195. *
  2196. * None Home to all axes with no parameters.
  2197. * With QUICK_HOME enabled XY will home together, then Z.
  2198. *
  2199. * Cartesian parameters
  2200. *
  2201. * X Home to the X endstop
  2202. * Y Home to the Y endstop
  2203. * Z Home to the Z endstop
  2204. *
  2205. */
  2206. inline void gcode_G28() {
  2207. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2208. if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("gcode_G28 >>>");
  2209. #endif
  2210. // Wait for planner moves to finish!
  2211. stepper.synchronize();
  2212. // For auto bed leveling, clear the level matrix
  2213. #if ENABLED(AUTO_BED_LEVELING_FEATURE)
  2214. planner.bed_level_matrix.set_to_identity();
  2215. #if ENABLED(DELTA)
  2216. reset_bed_level();
  2217. #endif
  2218. #endif
  2219. /**
  2220. * For mesh bed leveling deactivate the mesh calculations, will be turned
  2221. * on again when homing all axis
  2222. */
  2223. #if ENABLED(MESH_BED_LEVELING)
  2224. float pre_home_z = MESH_HOME_SEARCH_Z;
  2225. if (mbl.active()) {
  2226. // Save known Z position if already homed
  2227. if (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) {
  2228. pre_home_z = current_position[Z_AXIS];
  2229. pre_home_z += mbl.get_z(current_position[X_AXIS] - home_offset[X_AXIS],
  2230. current_position[Y_AXIS] - home_offset[Y_AXIS]);
  2231. }
  2232. mbl.set_active(false);
  2233. }
  2234. #endif
  2235. setup_for_endstop_move();
  2236. /**
  2237. * Directly after a reset this is all 0. Later we get a hint if we have
  2238. * to raise z or not.
  2239. */
  2240. set_destination_to_current();
  2241. feedrate = 0.0;
  2242. #if ENABLED(DELTA)
  2243. /**
  2244. * A delta can only safely home all axis at the same time
  2245. * all axis have to home at the same time
  2246. */
  2247. // Pretend the current position is 0,0,0
  2248. for (int i = X_AXIS; i <= Z_AXIS; i++) current_position[i] = 0;
  2249. sync_plan_position();
  2250. // Move all carriages up together until the first endstop is hit.
  2251. for (int i = X_AXIS; i <= Z_AXIS; i++) destination[i] = 3 * (Z_MAX_LENGTH);
  2252. feedrate = 1.732 * homing_feedrate[X_AXIS];
  2253. line_to_destination();
  2254. stepper.synchronize();
  2255. endstops.hit_on_purpose(); // clear endstop hit flags
  2256. // Destination reached
  2257. for (int i = X_AXIS; i <= Z_AXIS; i++) current_position[i] = destination[i];
  2258. // take care of back off and rehome now we are all at the top
  2259. HOMEAXIS(X);
  2260. HOMEAXIS(Y);
  2261. HOMEAXIS(Z);
  2262. sync_plan_position_delta();
  2263. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2264. if (DEBUGGING(LEVELING)) DEBUG_POS("(DELTA)", current_position);
  2265. #endif
  2266. #else // NOT DELTA
  2267. bool homeX = code_seen(axis_codes[X_AXIS]),
  2268. homeY = code_seen(axis_codes[Y_AXIS]),
  2269. homeZ = code_seen(axis_codes[Z_AXIS]);
  2270. home_all_axis = (!homeX && !homeY && !homeZ) || (homeX && homeY && homeZ);
  2271. #if Z_HOME_DIR > 0 // If homing away from BED do Z first
  2272. if (home_all_axis || homeZ) {
  2273. HOMEAXIS(Z);
  2274. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2275. if (DEBUGGING(LEVELING)) DEBUG_POS("> HOMEAXIS(Z)", current_position);
  2276. #endif
  2277. }
  2278. #elif defined(MIN_Z_HEIGHT_FOR_HOMING) && MIN_Z_HEIGHT_FOR_HOMING > 0
  2279. // Raise Z before homing any other axes and z is not already high enough (never lower z)
  2280. if (current_position[Z_AXIS] <= MIN_Z_HEIGHT_FOR_HOMING) {
  2281. destination[Z_AXIS] = MIN_Z_HEIGHT_FOR_HOMING;
  2282. feedrate = planner.max_feedrate[Z_AXIS] * 60; // feedrate (mm/m) = max_feedrate (mm/s)
  2283. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2284. if (DEBUGGING(LEVELING)) {
  2285. SERIAL_ECHOPAIR("Raise Z (before homing) to ", (MIN_Z_HEIGHT_FOR_HOMING));
  2286. SERIAL_EOL;
  2287. DEBUG_POS("> (home_all_axis || homeZ)", current_position);
  2288. DEBUG_POS("> (home_all_axis || homeZ)", destination);
  2289. }
  2290. #endif
  2291. line_to_destination();
  2292. stepper.synchronize();
  2293. /**
  2294. * Update the current Z position even if it currently not real from
  2295. * Z-home otherwise each call to line_to_destination() will want to
  2296. * move Z-axis by MIN_Z_HEIGHT_FOR_HOMING.
  2297. */
  2298. current_position[Z_AXIS] = destination[Z_AXIS];
  2299. }
  2300. #endif
  2301. #if ENABLED(QUICK_HOME)
  2302. if (home_all_axis || (homeX && homeY)) { // First diagonal move
  2303. current_position[X_AXIS] = current_position[Y_AXIS] = 0;
  2304. #if ENABLED(DUAL_X_CARRIAGE)
  2305. int x_axis_home_dir = x_home_dir(active_extruder);
  2306. extruder_duplication_enabled = false;
  2307. #else
  2308. int x_axis_home_dir = home_dir(X_AXIS);
  2309. #endif
  2310. sync_plan_position();
  2311. float mlx = max_length(X_AXIS), mly = max_length(Y_AXIS),
  2312. mlratio = mlx > mly ? mly / mlx : mlx / mly;
  2313. destination[X_AXIS] = 1.5 * mlx * x_axis_home_dir;
  2314. destination[Y_AXIS] = 1.5 * mly * home_dir(Y_AXIS);
  2315. feedrate = min(homing_feedrate[X_AXIS], homing_feedrate[Y_AXIS]) * sqrt(mlratio * mlratio + 1);
  2316. line_to_destination();
  2317. stepper.synchronize();
  2318. set_axis_is_at_home(X_AXIS);
  2319. set_axis_is_at_home(Y_AXIS);
  2320. sync_plan_position();
  2321. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2322. if (DEBUGGING(LEVELING)) DEBUG_POS("> QUICK_HOME 1", current_position);
  2323. #endif
  2324. destination[X_AXIS] = current_position[X_AXIS];
  2325. destination[Y_AXIS] = current_position[Y_AXIS];
  2326. line_to_destination();
  2327. feedrate = 0.0;
  2328. stepper.synchronize();
  2329. endstops.hit_on_purpose(); // clear endstop hit flags
  2330. current_position[X_AXIS] = destination[X_AXIS];
  2331. current_position[Y_AXIS] = destination[Y_AXIS];
  2332. #if DISABLED(SCARA)
  2333. current_position[Z_AXIS] = destination[Z_AXIS];
  2334. #endif
  2335. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2336. if (DEBUGGING(LEVELING)) DEBUG_POS("> QUICK_HOME 2", current_position);
  2337. #endif
  2338. }
  2339. #endif // QUICK_HOME
  2340. #if ENABLED(HOME_Y_BEFORE_X)
  2341. // Home Y
  2342. if (home_all_axis || homeY) HOMEAXIS(Y);
  2343. #endif
  2344. // Home X
  2345. if (home_all_axis || homeX) {
  2346. #if ENABLED(DUAL_X_CARRIAGE)
  2347. int tmp_extruder = active_extruder;
  2348. extruder_duplication_enabled = false;
  2349. active_extruder = !active_extruder;
  2350. HOMEAXIS(X);
  2351. inactive_extruder_x_pos = current_position[X_AXIS];
  2352. active_extruder = tmp_extruder;
  2353. HOMEAXIS(X);
  2354. // reset state used by the different modes
  2355. memcpy(raised_parked_position, current_position, sizeof(raised_parked_position));
  2356. delayed_move_time = 0;
  2357. active_extruder_parked = true;
  2358. #else
  2359. HOMEAXIS(X);
  2360. #endif
  2361. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2362. if (DEBUGGING(LEVELING)) DEBUG_POS("> homeX", current_position);
  2363. #endif
  2364. }
  2365. #if DISABLED(HOME_Y_BEFORE_X)
  2366. // Home Y
  2367. if (home_all_axis || homeY) {
  2368. HOMEAXIS(Y);
  2369. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2370. if (DEBUGGING(LEVELING)) DEBUG_POS("> homeY", current_position);
  2371. #endif
  2372. }
  2373. #endif
  2374. // Home Z last if homing towards the bed
  2375. #if Z_HOME_DIR < 0
  2376. if (home_all_axis || homeZ) {
  2377. #if ENABLED(Z_SAFE_HOMING)
  2378. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2379. if (DEBUGGING(LEVELING)) {
  2380. SERIAL_ECHOLNPGM("> Z_SAFE_HOMING >>>");
  2381. }
  2382. #endif
  2383. if (home_all_axis) {
  2384. /**
  2385. * At this point we already have Z at MIN_Z_HEIGHT_FOR_HOMING height
  2386. * No need to move Z any more as this height should already be safe
  2387. * enough to reach Z_SAFE_HOMING XY positions.
  2388. * Just make sure the planner is in sync.
  2389. */
  2390. sync_plan_position();
  2391. /**
  2392. * Set the Z probe (or just the nozzle) destination to the safe
  2393. * homing point
  2394. */
  2395. destination[X_AXIS] = round(Z_SAFE_HOMING_X_POINT - (X_PROBE_OFFSET_FROM_EXTRUDER));
  2396. destination[Y_AXIS] = round(Z_SAFE_HOMING_Y_POINT - (Y_PROBE_OFFSET_FROM_EXTRUDER));
  2397. destination[Z_AXIS] = current_position[Z_AXIS]; //z is already at the right height
  2398. feedrate = XY_TRAVEL_SPEED;
  2399. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2400. if (DEBUGGING(LEVELING)) {
  2401. DEBUG_POS("> Z_SAFE_HOMING > home_all_axis", current_position);
  2402. DEBUG_POS("> Z_SAFE_HOMING > home_all_axis", destination);
  2403. }
  2404. #endif
  2405. // Move in the XY plane
  2406. line_to_destination();
  2407. stepper.synchronize();
  2408. /**
  2409. * Update the current positions for XY, Z is still at least at
  2410. * MIN_Z_HEIGHT_FOR_HOMING height, no changes there.
  2411. */
  2412. current_position[X_AXIS] = destination[X_AXIS];
  2413. current_position[Y_AXIS] = destination[Y_AXIS];
  2414. // Home the Z axis
  2415. HOMEAXIS(Z);
  2416. }
  2417. else if (homeZ) { // Don't need to Home Z twice
  2418. // Let's see if X and Y are homed
  2419. if (axis_homed[X_AXIS] && axis_homed[Y_AXIS]) {
  2420. /**
  2421. * Make sure the Z probe is within the physical limits
  2422. * NOTE: This doesn't necessarily ensure the Z probe is also
  2423. * within the bed!
  2424. */
  2425. float cpx = current_position[X_AXIS], cpy = current_position[Y_AXIS];
  2426. if ( cpx >= X_MIN_POS - (X_PROBE_OFFSET_FROM_EXTRUDER)
  2427. && cpx <= X_MAX_POS - (X_PROBE_OFFSET_FROM_EXTRUDER)
  2428. && cpy >= Y_MIN_POS - (Y_PROBE_OFFSET_FROM_EXTRUDER)
  2429. && cpy <= Y_MAX_POS - (Y_PROBE_OFFSET_FROM_EXTRUDER)) {
  2430. // Home the Z axis
  2431. HOMEAXIS(Z);
  2432. }
  2433. else {
  2434. LCD_MESSAGEPGM(MSG_ZPROBE_OUT);
  2435. SERIAL_ECHO_START;
  2436. SERIAL_ECHOLNPGM(MSG_ZPROBE_OUT);
  2437. }
  2438. }
  2439. else {
  2440. axis_unhomed_error();
  2441. }
  2442. } // !home_all_axes && homeZ
  2443. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2444. if (DEBUGGING(LEVELING)) {
  2445. SERIAL_ECHOLNPGM("<<< Z_SAFE_HOMING");
  2446. }
  2447. #endif
  2448. #else // !Z_SAFE_HOMING
  2449. HOMEAXIS(Z);
  2450. #endif // !Z_SAFE_HOMING
  2451. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2452. if (DEBUGGING(LEVELING)) DEBUG_POS("> (home_all_axis || homeZ) > final", current_position);
  2453. #endif
  2454. } // home_all_axis || homeZ
  2455. #endif // Z_HOME_DIR < 0
  2456. sync_plan_position();
  2457. #endif // else DELTA
  2458. #if ENABLED(SCARA)
  2459. sync_plan_position_delta();
  2460. #endif
  2461. #if ENABLED(ENDSTOPS_ONLY_FOR_HOMING)
  2462. endstops.enable(false);
  2463. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2464. if (DEBUGGING(LEVELING)) {
  2465. SERIAL_ECHOLNPGM("ENDSTOPS_ONLY_FOR_HOMING endstops.enable(false)");
  2466. }
  2467. #endif
  2468. #endif
  2469. // Enable mesh leveling again
  2470. #if ENABLED(MESH_BED_LEVELING)
  2471. if (mbl.has_mesh()) {
  2472. if (home_all_axis || (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && homeZ)) {
  2473. current_position[Z_AXIS] = MESH_HOME_SEARCH_Z;
  2474. sync_plan_position();
  2475. mbl.set_active(true);
  2476. #if ENABLED(MESH_G28_REST_ORIGIN)
  2477. current_position[Z_AXIS] = 0.0;
  2478. set_destination_to_current();
  2479. feedrate = homing_feedrate[Z_AXIS];
  2480. line_to_destination();
  2481. stepper.synchronize();
  2482. #else
  2483. current_position[Z_AXIS] = MESH_HOME_SEARCH_Z -
  2484. mbl.get_z(current_position[X_AXIS] - home_offset[X_AXIS],
  2485. current_position[Y_AXIS] - home_offset[Y_AXIS]);
  2486. #endif
  2487. }
  2488. else if ((axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) && (homeX || homeY)) {
  2489. current_position[Z_AXIS] = pre_home_z;
  2490. sync_plan_position();
  2491. mbl.set_active(true);
  2492. current_position[Z_AXIS] = pre_home_z -
  2493. mbl.get_z(current_position[X_AXIS] - home_offset[X_AXIS],
  2494. current_position[Y_AXIS] - home_offset[Y_AXIS]);
  2495. }
  2496. }
  2497. #endif
  2498. feedrate = saved_feedrate;
  2499. feedrate_multiplier = saved_feedrate_multiplier;
  2500. refresh_cmd_timeout();
  2501. endstops.hit_on_purpose(); // clear endstop hit flags
  2502. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2503. if (DEBUGGING(LEVELING)) {
  2504. SERIAL_ECHOLNPGM("<<< gcode_G28");
  2505. }
  2506. #endif
  2507. report_current_position();
  2508. }
  2509. #if ENABLED(MESH_BED_LEVELING)
  2510. enum MeshLevelingState { MeshReport, MeshStart, MeshNext, MeshSet, MeshSetZOffset, MeshReset };
  2511. inline void _mbl_goto_xy(float x, float y) {
  2512. saved_feedrate = feedrate;
  2513. feedrate = homing_feedrate[X_AXIS];
  2514. current_position[Z_AXIS] = MESH_HOME_SEARCH_Z
  2515. #if MIN_Z_HEIGHT_FOR_HOMING > 0
  2516. + MIN_Z_HEIGHT_FOR_HOMING
  2517. #endif
  2518. ;
  2519. line_to_current_position();
  2520. current_position[X_AXIS] = x + home_offset[X_AXIS];
  2521. current_position[Y_AXIS] = y + home_offset[Y_AXIS];
  2522. line_to_current_position();
  2523. #if MIN_Z_HEIGHT_FOR_HOMING > 0
  2524. current_position[Z_AXIS] = MESH_HOME_SEARCH_Z;
  2525. line_to_current_position();
  2526. #endif
  2527. feedrate = saved_feedrate;
  2528. stepper.synchronize();
  2529. }
  2530. /**
  2531. * G29: Mesh-based Z probe, probes a grid and produces a
  2532. * mesh to compensate for variable bed height
  2533. *
  2534. * Parameters With MESH_BED_LEVELING:
  2535. *
  2536. * S0 Produce a mesh report
  2537. * S1 Start probing mesh points
  2538. * S2 Probe the next mesh point
  2539. * S3 Xn Yn Zn.nn Manually modify a single point
  2540. * S4 Zn.nn Set z offset. Positive away from bed, negative closer to bed.
  2541. * S5 Reset and disable mesh
  2542. *
  2543. * The S0 report the points as below
  2544. *
  2545. * +----> X-axis 1-n
  2546. * |
  2547. * |
  2548. * v Y-axis 1-n
  2549. *
  2550. */
  2551. inline void gcode_G29() {
  2552. static int probe_point = -1;
  2553. MeshLevelingState state = code_seen('S') ? (MeshLevelingState)code_value_short() : MeshReport;
  2554. if (state < 0 || state > 5) {
  2555. SERIAL_PROTOCOLLNPGM("S out of range (0-5).");
  2556. return;
  2557. }
  2558. int8_t px, py;
  2559. float z;
  2560. switch (state) {
  2561. case MeshReport:
  2562. if (mbl.has_mesh()) {
  2563. SERIAL_PROTOCOLPGM("State: ");
  2564. if (mbl.active())
  2565. SERIAL_PROTOCOLPGM("On");
  2566. else
  2567. SERIAL_PROTOCOLPGM("Off");
  2568. SERIAL_PROTOCOLPGM("\nNum X,Y: ");
  2569. SERIAL_PROTOCOL(MESH_NUM_X_POINTS);
  2570. SERIAL_PROTOCOLCHAR(',');
  2571. SERIAL_PROTOCOL(MESH_NUM_Y_POINTS);
  2572. SERIAL_PROTOCOLPGM("\nZ search height: ");
  2573. SERIAL_PROTOCOL(MESH_HOME_SEARCH_Z);
  2574. SERIAL_PROTOCOLPGM("\nZ offset: ");
  2575. SERIAL_PROTOCOL_F(mbl.z_offset, 5);
  2576. SERIAL_PROTOCOLLNPGM("\nMeasured points:");
  2577. for (py = 0; py < MESH_NUM_Y_POINTS; py++) {
  2578. for (px = 0; px < MESH_NUM_X_POINTS; px++) {
  2579. SERIAL_PROTOCOLPGM(" ");
  2580. SERIAL_PROTOCOL_F(mbl.z_values[py][px], 5);
  2581. }
  2582. SERIAL_EOL;
  2583. }
  2584. }
  2585. else
  2586. SERIAL_PROTOCOLLNPGM("Mesh bed leveling not active.");
  2587. break;
  2588. case MeshStart:
  2589. mbl.reset();
  2590. probe_point = 0;
  2591. enqueue_and_echo_commands_P(PSTR("G28\nG29 S2"));
  2592. break;
  2593. case MeshNext:
  2594. if (probe_point < 0) {
  2595. SERIAL_PROTOCOLLNPGM("Start mesh probing with \"G29 S1\" first.");
  2596. return;
  2597. }
  2598. // For each G29 S2...
  2599. if (probe_point == 0) {
  2600. // For the intial G29 S2 make Z a positive value (e.g., 4.0)
  2601. current_position[Z_AXIS] = MESH_HOME_SEARCH_Z;
  2602. sync_plan_position();
  2603. }
  2604. else {
  2605. // For G29 S2 after adjusting Z.
  2606. mbl.set_zigzag_z(probe_point - 1, current_position[Z_AXIS]);
  2607. }
  2608. // If there's another point to sample, move there with optional lift.
  2609. if (probe_point < (MESH_NUM_X_POINTS) * (MESH_NUM_Y_POINTS)) {
  2610. mbl.zigzag(probe_point, px, py);
  2611. _mbl_goto_xy(mbl.get_probe_x(px), mbl.get_probe_y(py));
  2612. probe_point++;
  2613. }
  2614. else {
  2615. // One last "return to the bed" (as originally coded) at completion
  2616. current_position[Z_AXIS] = MESH_HOME_SEARCH_Z
  2617. #if MIN_Z_HEIGHT_FOR_HOMING > 0
  2618. + MIN_Z_HEIGHT_FOR_HOMING
  2619. #endif
  2620. ;
  2621. line_to_current_position();
  2622. stepper.synchronize();
  2623. // After recording the last point, activate the mbl and home
  2624. SERIAL_PROTOCOLLNPGM("Mesh probing done.");
  2625. probe_point = -1;
  2626. mbl.set_has_mesh(true);
  2627. enqueue_and_echo_commands_P(PSTR("G28"));
  2628. }
  2629. break;
  2630. case MeshSet:
  2631. if (code_seen('X')) {
  2632. px = code_value_long() - 1;
  2633. if (px < 0 || px >= MESH_NUM_X_POINTS) {
  2634. SERIAL_PROTOCOLPGM("X out of range (1-" STRINGIFY(MESH_NUM_X_POINTS) ").\n");
  2635. return;
  2636. }
  2637. }
  2638. else {
  2639. SERIAL_PROTOCOLPGM("X not entered.\n");
  2640. return;
  2641. }
  2642. if (code_seen('Y')) {
  2643. py = code_value_long() - 1;
  2644. if (py < 0 || py >= MESH_NUM_Y_POINTS) {
  2645. SERIAL_PROTOCOLPGM("Y out of range (1-" STRINGIFY(MESH_NUM_Y_POINTS) ").\n");
  2646. return;
  2647. }
  2648. }
  2649. else {
  2650. SERIAL_PROTOCOLPGM("Y not entered.\n");
  2651. return;
  2652. }
  2653. if (code_seen('Z')) {
  2654. z = code_value();
  2655. }
  2656. else {
  2657. SERIAL_PROTOCOLPGM("Z not entered.\n");
  2658. return;
  2659. }
  2660. mbl.z_values[py][px] = z;
  2661. break;
  2662. case MeshSetZOffset:
  2663. if (code_seen('Z')) {
  2664. z = code_value();
  2665. }
  2666. else {
  2667. SERIAL_PROTOCOLPGM("Z not entered.\n");
  2668. return;
  2669. }
  2670. mbl.z_offset = z;
  2671. break;
  2672. case MeshReset:
  2673. if (mbl.active()) {
  2674. current_position[Z_AXIS] +=
  2675. mbl.get_z(current_position[X_AXIS] - home_offset[X_AXIS],
  2676. current_position[Y_AXIS] - home_offset[Y_AXIS]) - MESH_HOME_SEARCH_Z;
  2677. mbl.reset();
  2678. sync_plan_position();
  2679. }
  2680. else
  2681. mbl.reset();
  2682. } // switch(state)
  2683. report_current_position();
  2684. }
  2685. #elif ENABLED(AUTO_BED_LEVELING_FEATURE)
  2686. void out_of_range_error(const char* p_edge) {
  2687. SERIAL_PROTOCOLPGM("?Probe ");
  2688. serialprintPGM(p_edge);
  2689. SERIAL_PROTOCOLLNPGM(" position out of range.");
  2690. }
  2691. /**
  2692. * G29: Detailed Z probe, probes the bed at 3 or more points.
  2693. * Will fail if the printer has not been homed with G28.
  2694. *
  2695. * Enhanced G29 Auto Bed Leveling Probe Routine
  2696. *
  2697. * Parameters With AUTO_BED_LEVELING_GRID:
  2698. *
  2699. * P Set the size of the grid that will be probed (P x P points).
  2700. * Not supported by non-linear delta printer bed leveling.
  2701. * Example: "G29 P4"
  2702. *
  2703. * S Set the XY travel speed between probe points (in mm/min)
  2704. *
  2705. * D Dry-Run mode. Just evaluate the bed Topology - Don't apply
  2706. * or clean the rotation Matrix. Useful to check the topology
  2707. * after a first run of G29.
  2708. *
  2709. * V Set the verbose level (0-4). Example: "G29 V3"
  2710. *
  2711. * T Generate a Bed Topology Report. Example: "G29 P5 T" for a detailed report.
  2712. * This is useful for manual bed leveling and finding flaws in the bed (to
  2713. * assist with part placement).
  2714. * Not supported by non-linear delta printer bed leveling.
  2715. *
  2716. * F Set the Front limit of the probing grid
  2717. * B Set the Back limit of the probing grid
  2718. * L Set the Left limit of the probing grid
  2719. * R Set the Right limit of the probing grid
  2720. *
  2721. * Global Parameters:
  2722. *
  2723. * E/e By default G29 will engage the Z probe, test the bed, then disengage.
  2724. * Include "E" to engage/disengage the Z probe for each sample.
  2725. * There's no extra effect if you have a fixed Z probe.
  2726. * Usage: "G29 E" or "G29 e"
  2727. *
  2728. */
  2729. inline void gcode_G29() {
  2730. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2731. if (DEBUGGING(LEVELING)) {
  2732. SERIAL_ECHOLNPGM("gcode_G29 >>>");
  2733. DEBUG_POS("", current_position);
  2734. }
  2735. #endif
  2736. // Don't allow auto-leveling without homing first
  2737. if (!axis_homed[X_AXIS] || !axis_homed[Y_AXIS] || !axis_homed[Z_AXIS]) {
  2738. axis_unhomed_error(true);
  2739. return;
  2740. }
  2741. int verbose_level = code_seen('V') ? code_value_short() : 1;
  2742. if (verbose_level < 0 || verbose_level > 4) {
  2743. SERIAL_ECHOLNPGM("?(V)erbose Level is implausible (0-4).");
  2744. return;
  2745. }
  2746. bool dryrun = code_seen('D'),
  2747. deploy_probe_for_each_reading = code_seen('E');
  2748. #if ENABLED(AUTO_BED_LEVELING_GRID)
  2749. #if DISABLED(DELTA)
  2750. bool do_topography_map = verbose_level > 2 || code_seen('T');
  2751. #endif
  2752. if (verbose_level > 0) {
  2753. SERIAL_PROTOCOLPGM("G29 Auto Bed Leveling\n");
  2754. if (dryrun) SERIAL_ECHOLNPGM("Running in DRY-RUN mode");
  2755. }
  2756. int auto_bed_leveling_grid_points = AUTO_BED_LEVELING_GRID_POINTS;
  2757. #if DISABLED(DELTA)
  2758. if (code_seen('P')) auto_bed_leveling_grid_points = code_value_short();
  2759. if (auto_bed_leveling_grid_points < 2) {
  2760. SERIAL_PROTOCOLPGM("?Number of probed (P)oints is implausible (2 minimum).\n");
  2761. return;
  2762. }
  2763. #endif
  2764. xy_travel_speed = code_seen('S') ? code_value_short() : XY_TRAVEL_SPEED;
  2765. int left_probe_bed_position = code_seen('L') ? code_value_short() : LEFT_PROBE_BED_POSITION,
  2766. right_probe_bed_position = code_seen('R') ? code_value_short() : RIGHT_PROBE_BED_POSITION,
  2767. front_probe_bed_position = code_seen('F') ? code_value_short() : FRONT_PROBE_BED_POSITION,
  2768. back_probe_bed_position = code_seen('B') ? code_value_short() : BACK_PROBE_BED_POSITION;
  2769. bool left_out_l = left_probe_bed_position < MIN_PROBE_X,
  2770. left_out = left_out_l || left_probe_bed_position > right_probe_bed_position - (MIN_PROBE_EDGE),
  2771. right_out_r = right_probe_bed_position > MAX_PROBE_X,
  2772. right_out = right_out_r || right_probe_bed_position < left_probe_bed_position + MIN_PROBE_EDGE,
  2773. front_out_f = front_probe_bed_position < MIN_PROBE_Y,
  2774. front_out = front_out_f || front_probe_bed_position > back_probe_bed_position - (MIN_PROBE_EDGE),
  2775. back_out_b = back_probe_bed_position > MAX_PROBE_Y,
  2776. back_out = back_out_b || back_probe_bed_position < front_probe_bed_position + MIN_PROBE_EDGE;
  2777. if (left_out || right_out || front_out || back_out) {
  2778. if (left_out) {
  2779. out_of_range_error(PSTR("(L)eft"));
  2780. left_probe_bed_position = left_out_l ? MIN_PROBE_X : right_probe_bed_position - (MIN_PROBE_EDGE);
  2781. }
  2782. if (right_out) {
  2783. out_of_range_error(PSTR("(R)ight"));
  2784. right_probe_bed_position = right_out_r ? MAX_PROBE_X : left_probe_bed_position + MIN_PROBE_EDGE;
  2785. }
  2786. if (front_out) {
  2787. out_of_range_error(PSTR("(F)ront"));
  2788. front_probe_bed_position = front_out_f ? MIN_PROBE_Y : back_probe_bed_position - (MIN_PROBE_EDGE);
  2789. }
  2790. if (back_out) {
  2791. out_of_range_error(PSTR("(B)ack"));
  2792. back_probe_bed_position = back_out_b ? MAX_PROBE_Y : front_probe_bed_position + MIN_PROBE_EDGE;
  2793. }
  2794. return;
  2795. }
  2796. #endif // AUTO_BED_LEVELING_GRID
  2797. if (!dryrun) {
  2798. #if ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(DELTA)
  2799. if (DEBUGGING(LEVELING)) {
  2800. vector_3 corrected_position = planner.adjusted_position();
  2801. DEBUG_POS("BEFORE matrix.set_to_identity", corrected_position);
  2802. DEBUG_POS("BEFORE matrix.set_to_identity", current_position);
  2803. }
  2804. #endif
  2805. // make sure the bed_level_rotation_matrix is identity or the planner will get it wrong
  2806. planner.bed_level_matrix.set_to_identity();
  2807. #if ENABLED(DELTA)
  2808. reset_bed_level();
  2809. #else //!DELTA
  2810. //vector_3 corrected_position = planner.adjusted_position();
  2811. //corrected_position.debug("position before G29");
  2812. vector_3 uncorrected_position = planner.adjusted_position();
  2813. //uncorrected_position.debug("position during G29");
  2814. current_position[X_AXIS] = uncorrected_position.x;
  2815. current_position[Y_AXIS] = uncorrected_position.y;
  2816. current_position[Z_AXIS] = uncorrected_position.z;
  2817. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2818. if (DEBUGGING(LEVELING)) DEBUG_POS("AFTER matrix.set_to_identity", uncorrected_position);
  2819. #endif
  2820. sync_plan_position();
  2821. #endif // !DELTA
  2822. }
  2823. #if ENABLED(Z_PROBE_SLED)
  2824. dock_sled(false); // engage (un-dock) the Z probe
  2825. #elif ENABLED(FIX_MOUNTED_PROBE) || ENABLED(MECHANICAL_PROBE) || ENABLED(Z_PROBE_ALLEN_KEY) || (ENABLED(DELTA) && SERVO_LEVELING)
  2826. deploy_z_probe();
  2827. #endif
  2828. stepper.synchronize();
  2829. setup_for_endstop_move();
  2830. feedrate = homing_feedrate[Z_AXIS];
  2831. bed_leveling_in_progress = true;
  2832. #if ENABLED(AUTO_BED_LEVELING_GRID)
  2833. // probe at the points of a lattice grid
  2834. const int xGridSpacing = (right_probe_bed_position - left_probe_bed_position) / (auto_bed_leveling_grid_points - 1),
  2835. yGridSpacing = (back_probe_bed_position - front_probe_bed_position) / (auto_bed_leveling_grid_points - 1);
  2836. #if ENABLED(DELTA)
  2837. delta_grid_spacing[0] = xGridSpacing;
  2838. delta_grid_spacing[1] = yGridSpacing;
  2839. float zoffset = zprobe_zoffset;
  2840. if (code_seen(axis_codes[Z_AXIS])) zoffset += code_value();
  2841. #else // !DELTA
  2842. /**
  2843. * solve the plane equation ax + by + d = z
  2844. * A is the matrix with rows [x y 1] for all the probed points
  2845. * B is the vector of the Z positions
  2846. * the normal vector to the plane is formed by the coefficients of the
  2847. * plane equation in the standard form, which is Vx*x+Vy*y+Vz*z+d = 0
  2848. * so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z
  2849. */
  2850. int abl2 = auto_bed_leveling_grid_points * auto_bed_leveling_grid_points;
  2851. double eqnAMatrix[abl2 * 3], // "A" matrix of the linear system of equations
  2852. eqnBVector[abl2], // "B" vector of Z points
  2853. mean = 0.0;
  2854. int8_t indexIntoAB[auto_bed_leveling_grid_points][auto_bed_leveling_grid_points];
  2855. #endif // !DELTA
  2856. int probePointCounter = 0;
  2857. bool zig = (auto_bed_leveling_grid_points & 1) ? true : false; //always end at [RIGHT_PROBE_BED_POSITION, BACK_PROBE_BED_POSITION]
  2858. for (int yCount = 0; yCount < auto_bed_leveling_grid_points; yCount++) {
  2859. double yProbe = front_probe_bed_position + yGridSpacing * yCount;
  2860. int xStart, xStop, xInc;
  2861. if (zig) {
  2862. xStart = 0;
  2863. xStop = auto_bed_leveling_grid_points;
  2864. xInc = 1;
  2865. }
  2866. else {
  2867. xStart = auto_bed_leveling_grid_points - 1;
  2868. xStop = -1;
  2869. xInc = -1;
  2870. }
  2871. zig = !zig;
  2872. for (int xCount = xStart; xCount != xStop; xCount += xInc) {
  2873. double xProbe = left_probe_bed_position + xGridSpacing * xCount;
  2874. // raise extruder
  2875. float measured_z,
  2876. z_before = probePointCounter ? Z_RAISE_BETWEEN_PROBINGS + current_position[Z_AXIS] : Z_RAISE_BEFORE_PROBING + home_offset[Z_AXIS];
  2877. if (probePointCounter) {
  2878. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2879. if (DEBUGGING(LEVELING)) {
  2880. SERIAL_ECHOPAIR("z_before = (between) ", (Z_RAISE_BETWEEN_PROBINGS + current_position[Z_AXIS]));
  2881. SERIAL_EOL;
  2882. }
  2883. #endif
  2884. }
  2885. else {
  2886. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2887. if (DEBUGGING(LEVELING)) {
  2888. SERIAL_ECHOPAIR("z_before = (before) ", Z_RAISE_BEFORE_PROBING + home_offset[Z_AXIS]);
  2889. SERIAL_EOL;
  2890. }
  2891. #endif
  2892. }
  2893. #if ENABLED(DELTA)
  2894. // Avoid probing the corners (outside the round or hexagon print surface) on a delta printer.
  2895. float distance_from_center = sqrt(xProbe * xProbe + yProbe * yProbe);
  2896. if (distance_from_center > DELTA_PROBEABLE_RADIUS) continue;
  2897. #endif //DELTA
  2898. ProbeAction act;
  2899. if (deploy_probe_for_each_reading) // G29 E - Stow between probes
  2900. act = ProbeDeployAndStow;
  2901. else if (yCount == 0 && xCount == xStart)
  2902. act = ProbeDeploy;
  2903. else if (yCount == auto_bed_leveling_grid_points - 1 && xCount == xStop - xInc)
  2904. act = ProbeStow;
  2905. else
  2906. act = ProbeStay;
  2907. measured_z = probe_pt(xProbe, yProbe, z_before, act, verbose_level);
  2908. #if DISABLED(DELTA)
  2909. mean += measured_z;
  2910. eqnBVector[probePointCounter] = measured_z;
  2911. eqnAMatrix[probePointCounter + 0 * abl2] = xProbe;
  2912. eqnAMatrix[probePointCounter + 1 * abl2] = yProbe;
  2913. eqnAMatrix[probePointCounter + 2 * abl2] = 1;
  2914. indexIntoAB[xCount][yCount] = probePointCounter;
  2915. #else
  2916. bed_level[xCount][yCount] = measured_z + zoffset;
  2917. #endif
  2918. probePointCounter++;
  2919. idle();
  2920. } //xProbe
  2921. } //yProbe
  2922. #if ENABLED(DEBUG_LEVELING_FEATURE)
  2923. if (DEBUGGING(LEVELING)) DEBUG_POS("> probing complete", current_position);
  2924. #endif
  2925. clean_up_after_endstop_move();
  2926. #if ENABLED(DELTA)
  2927. if (!dryrun) extrapolate_unprobed_bed_level();
  2928. print_bed_level();
  2929. #else // !DELTA
  2930. // solve lsq problem
  2931. double plane_equation_coefficients[3];
  2932. qr_solve(plane_equation_coefficients, abl2, 3, eqnAMatrix, eqnBVector);
  2933. mean /= abl2;
  2934. if (verbose_level) {
  2935. SERIAL_PROTOCOLPGM("Eqn coefficients: a: ");
  2936. SERIAL_PROTOCOL_F(plane_equation_coefficients[0], 8);
  2937. SERIAL_PROTOCOLPGM(" b: ");
  2938. SERIAL_PROTOCOL_F(plane_equation_coefficients[1], 8);
  2939. SERIAL_PROTOCOLPGM(" d: ");
  2940. SERIAL_PROTOCOL_F(plane_equation_coefficients[2], 8);
  2941. SERIAL_EOL;
  2942. if (verbose_level > 2) {
  2943. SERIAL_PROTOCOLPGM("Mean of sampled points: ");
  2944. SERIAL_PROTOCOL_F(mean, 8);
  2945. SERIAL_EOL;
  2946. }
  2947. }
  2948. if (!dryrun) set_bed_level_equation_lsq(plane_equation_coefficients);
  2949. // Show the Topography map if enabled
  2950. if (do_topography_map) {
  2951. SERIAL_PROTOCOLPGM(" \nBed Height Topography: \n");
  2952. SERIAL_PROTOCOLPGM(" +--- BACK --+\n");
  2953. SERIAL_PROTOCOLPGM(" | |\n");
  2954. SERIAL_PROTOCOLPGM(" L | (+) | R\n");
  2955. SERIAL_PROTOCOLPGM(" E | | I\n");
  2956. SERIAL_PROTOCOLPGM(" F | (-) N (+) | G\n");
  2957. SERIAL_PROTOCOLPGM(" T | | H\n");
  2958. SERIAL_PROTOCOLPGM(" | (-) | T\n");
  2959. SERIAL_PROTOCOLPGM(" | |\n");
  2960. SERIAL_PROTOCOLPGM(" O-- FRONT --+\n");
  2961. SERIAL_PROTOCOLPGM(" (0,0)\n");
  2962. float min_diff = 999;
  2963. for (int yy = auto_bed_leveling_grid_points - 1; yy >= 0; yy--) {
  2964. for (int xx = 0; xx < auto_bed_leveling_grid_points; xx++) {
  2965. int ind = indexIntoAB[xx][yy];
  2966. float diff = eqnBVector[ind] - mean;
  2967. float x_tmp = eqnAMatrix[ind + 0 * abl2],
  2968. y_tmp = eqnAMatrix[ind + 1 * abl2],
  2969. z_tmp = 0;
  2970. apply_rotation_xyz(planner.bed_level_matrix, x_tmp, y_tmp, z_tmp);
  2971. NOMORE(min_diff, eqnBVector[ind] - z_tmp);
  2972. if (diff >= 0.0)
  2973. SERIAL_PROTOCOLPGM(" +"); // Include + for column alignment
  2974. else
  2975. SERIAL_PROTOCOLCHAR(' ');
  2976. SERIAL_PROTOCOL_F(diff, 5);
  2977. } // xx
  2978. SERIAL_EOL;
  2979. } // yy
  2980. SERIAL_EOL;
  2981. if (verbose_level > 3) {
  2982. SERIAL_PROTOCOLPGM(" \nCorrected Bed Height vs. Bed Topology: \n");
  2983. for (int yy = auto_bed_leveling_grid_points - 1; yy >= 0; yy--) {
  2984. for (int xx = 0; xx < auto_bed_leveling_grid_points; xx++) {
  2985. int ind = indexIntoAB[xx][yy];
  2986. float x_tmp = eqnAMatrix[ind + 0 * abl2],
  2987. y_tmp = eqnAMatrix[ind + 1 * abl2],
  2988. z_tmp = 0;
  2989. apply_rotation_xyz(planner.bed_level_matrix, x_tmp, y_tmp, z_tmp);
  2990. float diff = eqnBVector[ind] - z_tmp - min_diff;
  2991. if (diff >= 0.0)
  2992. SERIAL_PROTOCOLPGM(" +");
  2993. // Include + for column alignment
  2994. else
  2995. SERIAL_PROTOCOLCHAR(' ');
  2996. SERIAL_PROTOCOL_F(diff, 5);
  2997. } // xx
  2998. SERIAL_EOL;
  2999. } // yy
  3000. SERIAL_EOL;
  3001. }
  3002. } //do_topography_map
  3003. #endif //!DELTA
  3004. #else // !AUTO_BED_LEVELING_GRID
  3005. #if ENABLED(DEBUG_LEVELING_FEATURE)
  3006. if (DEBUGGING(LEVELING)) {
  3007. SERIAL_ECHOLNPGM("> 3-point Leveling");
  3008. }
  3009. #endif
  3010. // Actions for each probe
  3011. ProbeAction p1, p2, p3;
  3012. if (deploy_probe_for_each_reading)
  3013. p1 = p2 = p3 = ProbeDeployAndStow;
  3014. else
  3015. p1 = ProbeDeploy, p2 = ProbeStay, p3 = ProbeStow;
  3016. // Probe at 3 arbitrary points
  3017. float z_at_pt_1 = probe_pt( ABL_PROBE_PT_1_X + home_offset[X_AXIS],
  3018. ABL_PROBE_PT_1_Y + home_offset[Y_AXIS],
  3019. Z_RAISE_BEFORE_PROBING + home_offset[Z_AXIS],
  3020. p1, verbose_level),
  3021. z_at_pt_2 = probe_pt( ABL_PROBE_PT_2_X + home_offset[X_AXIS],
  3022. ABL_PROBE_PT_2_Y + home_offset[Y_AXIS],
  3023. current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS,
  3024. p2, verbose_level),
  3025. z_at_pt_3 = probe_pt( ABL_PROBE_PT_3_X + home_offset[X_AXIS],
  3026. ABL_PROBE_PT_3_Y + home_offset[Y_AXIS],
  3027. current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS,
  3028. p3, verbose_level);
  3029. clean_up_after_endstop_move();
  3030. if (!dryrun) set_bed_level_equation_3pts(z_at_pt_1, z_at_pt_2, z_at_pt_3);
  3031. #endif // !AUTO_BED_LEVELING_GRID
  3032. #if ENABLED(DELTA)
  3033. // Allen Key Probe for Delta
  3034. #if ENABLED(Z_PROBE_ALLEN_KEY) || SERVO_LEVELING
  3035. stow_z_probe();
  3036. #else
  3037. raise_z_after_probing(); // for non Allen Key probes, such as simple mechanical probe
  3038. #endif
  3039. #else // !DELTA
  3040. if (verbose_level > 0)
  3041. planner.bed_level_matrix.debug(" \n\nBed Level Correction Matrix:");
  3042. if (!dryrun) {
  3043. /**
  3044. * Correct the Z height difference from Z probe position and nozzle tip position.
  3045. * The Z height on homing is measured by Z probe, but the Z probe is quite far
  3046. * from the nozzle. When the bed is uneven, this height must be corrected.
  3047. */
  3048. float x_tmp = current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER,
  3049. y_tmp = current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER,
  3050. z_tmp = current_position[Z_AXIS],
  3051. real_z = stepper.get_axis_position_mm(Z_AXIS); //get the real Z (since planner.adjusted_position is now correcting the plane)
  3052. #if ENABLED(DEBUG_LEVELING_FEATURE)
  3053. if (DEBUGGING(LEVELING)) {
  3054. SERIAL_ECHOPAIR("> BEFORE apply_rotation_xyz > z_tmp = ", z_tmp);
  3055. SERIAL_EOL;
  3056. SERIAL_ECHOPAIR("> BEFORE apply_rotation_xyz > real_z = ", real_z);
  3057. SERIAL_EOL;
  3058. }
  3059. #endif
  3060. // Apply the correction sending the Z probe offset
  3061. apply_rotation_xyz(planner.bed_level_matrix, x_tmp, y_tmp, z_tmp);
  3062. /*
  3063. * Get the current Z position and send it to the planner.
  3064. *
  3065. * >> (z_tmp - real_z) : The rotated current Z minus the uncorrected Z
  3066. * (most recent planner.set_position_mm/sync_plan_position)
  3067. *
  3068. * >> zprobe_zoffset : Z distance from nozzle to Z probe
  3069. * (set by default, M851, EEPROM, or Menu)
  3070. *
  3071. * >> Z_RAISE_AFTER_PROBING : The distance the Z probe will have lifted
  3072. * after the last probe
  3073. *
  3074. * >> Should home_offset[Z_AXIS] be included?
  3075. *
  3076. *
  3077. * Discussion: home_offset[Z_AXIS] was applied in G28 to set the
  3078. * starting Z. If Z is not tweaked in G29 -and- the Z probe in G29 is
  3079. * not actually "homing" Z... then perhaps it should not be included
  3080. * here. The purpose of home_offset[] is to adjust for inaccurate
  3081. * endstops, not for reasonably accurate probes. If it were added
  3082. * here, it could be seen as a compensating factor for the Z probe.
  3083. */
  3084. #if ENABLED(DEBUG_LEVELING_FEATURE)
  3085. if (DEBUGGING(LEVELING)) {
  3086. SERIAL_ECHOPAIR("> AFTER apply_rotation_xyz > z_tmp = ", z_tmp);
  3087. SERIAL_EOL;
  3088. }
  3089. #endif
  3090. current_position[Z_AXIS] = -zprobe_zoffset + (z_tmp - real_z)
  3091. #if ENABLED(HAS_SERVO_ENDSTOPS) || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED)
  3092. + Z_RAISE_AFTER_PROBING
  3093. #endif
  3094. ;
  3095. // current_position[Z_AXIS] += home_offset[Z_AXIS]; // The Z probe determines Z=0, not "Z home"
  3096. sync_plan_position();
  3097. #if ENABLED(DEBUG_LEVELING_FEATURE)
  3098. if (DEBUGGING(LEVELING)) DEBUG_POS("> corrected Z in G29", current_position);
  3099. #endif
  3100. }
  3101. // Sled assembly for Cartesian bots
  3102. #if ENABLED(Z_PROBE_SLED)
  3103. dock_sled(true); // dock the sled
  3104. #else
  3105. // Raise Z axis for non-delta and non servo based probes
  3106. #if DISABLED(HAS_SERVO_ENDSTOPS) && DISABLED(Z_PROBE_ALLEN_KEY) && DISABLED(Z_PROBE_SLED)
  3107. raise_z_after_probing();
  3108. #endif
  3109. #endif
  3110. #endif // !DELTA
  3111. #if ENABLED(MECHANICAL_PROBE)
  3112. stow_z_probe();
  3113. #endif
  3114. #ifdef Z_PROBE_END_SCRIPT
  3115. #if ENABLED(DEBUG_LEVELING_FEATURE)
  3116. if (DEBUGGING(LEVELING)) {
  3117. SERIAL_ECHO("Z Probe End Script: ");
  3118. SERIAL_ECHOLNPGM(Z_PROBE_END_SCRIPT);
  3119. }
  3120. #endif
  3121. enqueue_and_echo_commands_P(PSTR(Z_PROBE_END_SCRIPT));
  3122. #if HAS_BED_PROBE
  3123. endstops.enable_z_probe(false);
  3124. #endif
  3125. stepper.synchronize();
  3126. #endif
  3127. #if ENABLED(DEBUG_LEVELING_FEATURE)
  3128. if (DEBUGGING(LEVELING)) {
  3129. SERIAL_ECHOLNPGM("<<< gcode_G29");
  3130. }
  3131. #endif
  3132. bed_leveling_in_progress = false;
  3133. report_current_position();
  3134. KEEPALIVE_STATE(IN_HANDLER);
  3135. }
  3136. #if DISABLED(Z_PROBE_SLED) // could be avoided
  3137. /**
  3138. * G30: Do a single Z probe at the current XY
  3139. */
  3140. inline void gcode_G30() {
  3141. #if ENABLED(HAS_SERVO_ENDSTOPS)
  3142. raise_z_for_servo();
  3143. #endif
  3144. deploy_z_probe(); // Engage Z Servo endstop if available. Z_PROBE_SLED is missed here.
  3145. stepper.synchronize();
  3146. // TODO: clear the leveling matrix or the planner will be set incorrectly
  3147. setup_for_endstop_move(); // Too late. Must be done before deploying.
  3148. feedrate = homing_feedrate[Z_AXIS];
  3149. run_z_probe();
  3150. SERIAL_PROTOCOLPGM("Bed X: ");
  3151. SERIAL_PROTOCOL(current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER + 0.0001);
  3152. SERIAL_PROTOCOLPGM(" Y: ");
  3153. SERIAL_PROTOCOL(current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER + 0.0001);
  3154. SERIAL_PROTOCOLPGM(" Z: ");
  3155. SERIAL_PROTOCOL(current_position[Z_AXIS] + 0.0001);
  3156. SERIAL_EOL;
  3157. clean_up_after_endstop_move(); // Too early. must be done after the stowing.
  3158. #if ENABLED(HAS_SERVO_ENDSTOPS)
  3159. raise_z_for_servo();
  3160. #endif
  3161. stow_z_probe(false); // Retract Z Servo endstop if available. Z_PROBE_SLED is missed here.
  3162. report_current_position();
  3163. }
  3164. #endif //!Z_PROBE_SLED
  3165. #endif //AUTO_BED_LEVELING_FEATURE
  3166. /**
  3167. * G92: Set current position to given X Y Z E
  3168. */
  3169. inline void gcode_G92() {
  3170. bool didE = code_seen(axis_codes[E_AXIS]);
  3171. if (!didE) stepper.synchronize();
  3172. bool didXYZ = false;
  3173. for (int i = 0; i < NUM_AXIS; i++) {
  3174. if (code_seen(axis_codes[i])) {
  3175. float p = current_position[i],
  3176. v = code_value();
  3177. current_position[i] = v;
  3178. if (i != E_AXIS) {
  3179. position_shift[i] += v - p; // Offset the coordinate space
  3180. update_software_endstops((AxisEnum)i);
  3181. didXYZ = true;
  3182. }
  3183. }
  3184. }
  3185. if (didXYZ) {
  3186. #if ENABLED(DELTA) || ENABLED(SCARA)
  3187. sync_plan_position_delta();
  3188. #else
  3189. sync_plan_position();
  3190. #endif
  3191. }
  3192. else if (didE) {
  3193. sync_plan_position_e();
  3194. }
  3195. }
  3196. #if ENABLED(ULTIPANEL)
  3197. /**
  3198. * M0: // M0 - Unconditional stop - Wait for user button press on LCD
  3199. * M1: // M1 - Conditional stop - Wait for user button press on LCD
  3200. */
  3201. inline void gcode_M0_M1() {
  3202. char* args = current_command_args;
  3203. uint8_t test_value = 12;
  3204. SERIAL_ECHOPAIR("TEST", test_value);
  3205. millis_t codenum = 0;
  3206. bool hasP = false, hasS = false;
  3207. if (code_seen('P')) {
  3208. codenum = code_value_short(); // milliseconds to wait
  3209. hasP = codenum > 0;
  3210. }
  3211. if (code_seen('S')) {
  3212. codenum = code_value() * 1000UL; // seconds to wait
  3213. hasS = codenum > 0;
  3214. }
  3215. if (!hasP && !hasS && *args != '\0')
  3216. lcd_setstatus(args, true);
  3217. else {
  3218. LCD_MESSAGEPGM(MSG_USERWAIT);
  3219. #if ENABLED(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0
  3220. dontExpireStatus();
  3221. #endif
  3222. }
  3223. lcd_ignore_click();
  3224. stepper.synchronize();
  3225. refresh_cmd_timeout();
  3226. if (codenum > 0) {
  3227. codenum += previous_cmd_ms; // wait until this time for a click
  3228. KEEPALIVE_STATE(PAUSED_FOR_USER);
  3229. while (PENDING(millis(), codenum) && !lcd_clicked()) idle();
  3230. KEEPALIVE_STATE(IN_HANDLER);
  3231. lcd_ignore_click(false);
  3232. }
  3233. else {
  3234. if (!lcd_detected()) return;
  3235. KEEPALIVE_STATE(PAUSED_FOR_USER);
  3236. while (!lcd_clicked()) idle();
  3237. KEEPALIVE_STATE(IN_HANDLER);
  3238. }
  3239. if (IS_SD_PRINTING)
  3240. LCD_MESSAGEPGM(MSG_RESUMING);
  3241. else
  3242. LCD_MESSAGEPGM(WELCOME_MSG);
  3243. }
  3244. #endif // ULTIPANEL
  3245. /**
  3246. * M17: Enable power on all stepper motors
  3247. */
  3248. inline void gcode_M17() {
  3249. LCD_MESSAGEPGM(MSG_NO_MOVE);
  3250. enable_all_steppers();
  3251. }
  3252. #if ENABLED(SDSUPPORT)
  3253. /**
  3254. * M20: List SD card to serial output
  3255. */
  3256. inline void gcode_M20() {
  3257. SERIAL_PROTOCOLLNPGM(MSG_BEGIN_FILE_LIST);
  3258. card.ls();
  3259. SERIAL_PROTOCOLLNPGM(MSG_END_FILE_LIST);
  3260. }
  3261. /**
  3262. * M21: Init SD Card
  3263. */
  3264. inline void gcode_M21() {
  3265. card.initsd();
  3266. }
  3267. /**
  3268. * M22: Release SD Card
  3269. */
  3270. inline void gcode_M22() {
  3271. card.release();
  3272. }
  3273. /**
  3274. * M23: Open a file
  3275. */
  3276. inline void gcode_M23() {
  3277. card.openFile(current_command_args, true);
  3278. }
  3279. /**
  3280. * M24: Start SD Print
  3281. */
  3282. inline void gcode_M24() {
  3283. card.startFileprint();
  3284. print_job_timer.start();
  3285. }
  3286. /**
  3287. * M25: Pause SD Print
  3288. */
  3289. inline void gcode_M25() {
  3290. card.pauseSDPrint();
  3291. }
  3292. /**
  3293. * M26: Set SD Card file index
  3294. */
  3295. inline void gcode_M26() {
  3296. if (card.cardOK && code_seen('S'))
  3297. card.setIndex(code_value_long());
  3298. }
  3299. /**
  3300. * M27: Get SD Card status
  3301. */
  3302. inline void gcode_M27() {
  3303. card.getStatus();
  3304. }
  3305. /**
  3306. * M28: Start SD Write
  3307. */
  3308. inline void gcode_M28() {
  3309. card.openFile(current_command_args, false);
  3310. }
  3311. /**
  3312. * M29: Stop SD Write
  3313. * Processed in write to file routine above
  3314. */
  3315. inline void gcode_M29() {
  3316. // card.saving = false;
  3317. }
  3318. /**
  3319. * M30 <filename>: Delete SD Card file
  3320. */
  3321. inline void gcode_M30() {
  3322. if (card.cardOK) {
  3323. card.closefile();
  3324. card.removeFile(current_command_args);
  3325. }
  3326. }
  3327. #endif //SDSUPPORT
  3328. /**
  3329. * M31: Get the time since the start of SD Print (or last M109)
  3330. */
  3331. inline void gcode_M31() {
  3332. millis_t t = print_job_timer.duration();
  3333. int min = t / 60, sec = t % 60;
  3334. char time[30];
  3335. sprintf_P(time, PSTR("%i min, %i sec"), min, sec);
  3336. SERIAL_ECHO_START;
  3337. SERIAL_ECHOLN(time);
  3338. lcd_setstatus(time);
  3339. thermalManager.autotempShutdown();
  3340. }
  3341. #if ENABLED(SDSUPPORT)
  3342. /**
  3343. * M32: Select file and start SD Print
  3344. */
  3345. inline void gcode_M32() {
  3346. if (card.sdprinting)
  3347. stepper.synchronize();
  3348. char* namestartpos = strchr(current_command_args, '!'); // Find ! to indicate filename string start.
  3349. if (!namestartpos)
  3350. namestartpos = current_command_args; // Default name position, 4 letters after the M
  3351. else
  3352. namestartpos++; //to skip the '!'
  3353. bool call_procedure = code_seen('P') && (seen_pointer < namestartpos);
  3354. if (card.cardOK) {
  3355. card.openFile(namestartpos, true, call_procedure);
  3356. if (code_seen('S') && seen_pointer < namestartpos) // "S" (must occur _before_ the filename!)
  3357. card.setIndex(code_value_long());
  3358. card.startFileprint();
  3359. // Procedure calls count as normal print time.
  3360. if (!call_procedure) print_job_timer.start();
  3361. }
  3362. }
  3363. #if ENABLED(LONG_FILENAME_HOST_SUPPORT)
  3364. /**
  3365. * M33: Get the long full path of a file or folder
  3366. *
  3367. * Parameters:
  3368. * <dospath> Case-insensitive DOS-style path to a file or folder
  3369. *
  3370. * Example:
  3371. * M33 miscel~1/armchair/armcha~1.gco
  3372. *
  3373. * Output:
  3374. * /Miscellaneous/Armchair/Armchair.gcode
  3375. */
  3376. inline void gcode_M33() {
  3377. card.printLongPath(current_command_args);
  3378. }
  3379. #endif
  3380. /**
  3381. * M928: Start SD Write
  3382. */
  3383. inline void gcode_M928() {
  3384. card.openLogFile(current_command_args);
  3385. }
  3386. #endif // SDSUPPORT
  3387. /**
  3388. * M42: Change pin status via GCode
  3389. *
  3390. * P<pin> Pin number (LED if omitted)
  3391. * S<byte> Pin status from 0 - 255
  3392. */
  3393. inline void gcode_M42() {
  3394. if (code_seen('S')) {
  3395. int pin_status = code_value_short();
  3396. if (pin_status < 0 || pin_status > 255) return;
  3397. int pin_number = code_seen('P') ? code_value_short() : LED_PIN;
  3398. if (pin_number < 0) return;
  3399. for (uint8_t i = 0; i < COUNT(sensitive_pins); i++)
  3400. if (pin_number == sensitive_pins[i]) return;
  3401. pinMode(pin_number, OUTPUT);
  3402. digitalWrite(pin_number, pin_status);
  3403. analogWrite(pin_number, pin_status);
  3404. #if FAN_COUNT > 0
  3405. switch (pin_number) {
  3406. #if HAS_FAN0
  3407. case FAN_PIN: fanSpeeds[0] = pin_status; break;
  3408. #endif
  3409. #if HAS_FAN1
  3410. case FAN1_PIN: fanSpeeds[1] = pin_status; break;
  3411. #endif
  3412. #if HAS_FAN2
  3413. case FAN2_PIN: fanSpeeds[2] = pin_status; break;
  3414. #endif
  3415. }
  3416. #endif
  3417. } // code_seen('S')
  3418. }
  3419. #if ENABLED(AUTO_BED_LEVELING_FEATURE) && ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
  3420. /**
  3421. * This is redundant since the SanityCheck.h already checks for a valid
  3422. * Z_MIN_PROBE_PIN, but here for clarity.
  3423. */
  3424. #if ENABLED(Z_MIN_PROBE_ENDSTOP)
  3425. #if !HAS_Z_MIN_PROBE_PIN
  3426. #error "You must define Z_MIN_PROBE_PIN to enable Z probe repeatability calculation."
  3427. #endif
  3428. #elif !HAS_Z_MIN
  3429. #error "You must define Z_MIN_PIN to enable Z probe repeatability calculation."
  3430. #endif
  3431. /**
  3432. * M48: Z probe repeatability measurement function.
  3433. *
  3434. * Usage:
  3435. * M48 <P#> <X#> <Y#> <V#> <E> <L#>
  3436. * P = Number of sampled points (4-50, default 10)
  3437. * X = Sample X position
  3438. * Y = Sample Y position
  3439. * V = Verbose level (0-4, default=1)
  3440. * E = Engage Z probe for each reading
  3441. * L = Number of legs of movement before probe
  3442. * S = Schizoid (Or Star if you prefer)
  3443. *
  3444. * This function assumes the bed has been homed. Specifically, that a G28 command
  3445. * as been issued prior to invoking the M48 Z probe repeatability measurement function.
  3446. * Any information generated by a prior G29 Bed leveling command will be lost and need to be
  3447. * regenerated.
  3448. */
  3449. inline void gcode_M48() {
  3450. if (!axis_homed[X_AXIS] || !axis_homed[Y_AXIS] || !axis_homed[Z_AXIS]) {
  3451. axis_unhomed_error(true);
  3452. return;
  3453. }
  3454. double sum = 0.0, mean = 0.0, sigma = 0.0, sample_set[50];
  3455. int8_t verbose_level = 1, n_samples = 10, n_legs = 0, schizoid_flag = 0;
  3456. if (code_seen('V')) {
  3457. verbose_level = code_value_short();
  3458. if (verbose_level < 0 || verbose_level > 4) {
  3459. SERIAL_PROTOCOLPGM("?Verbose Level not plausible (0-4).\n");
  3460. return;
  3461. }
  3462. }
  3463. if (verbose_level > 0)
  3464. SERIAL_PROTOCOLPGM("M48 Z-Probe Repeatability test\n");
  3465. if (code_seen('P')) {
  3466. n_samples = code_value_short();
  3467. if (n_samples < 4 || n_samples > 50) {
  3468. SERIAL_PROTOCOLPGM("?Sample size not plausible (4-50).\n");
  3469. return;
  3470. }
  3471. }
  3472. float X_current = current_position[X_AXIS],
  3473. Y_current = current_position[Y_AXIS],
  3474. Z_current = current_position[Z_AXIS],
  3475. X_probe_location = X_current + X_PROBE_OFFSET_FROM_EXTRUDER,
  3476. Y_probe_location = Y_current + Y_PROBE_OFFSET_FROM_EXTRUDER,
  3477. Z_start_location = Z_current + Z_RAISE_BEFORE_PROBING;
  3478. bool deploy_probe_for_each_reading = code_seen('E');
  3479. if (code_seen('X')) {
  3480. X_probe_location = code_value();
  3481. #if DISABLED(DELTA)
  3482. if (X_probe_location < MIN_PROBE_X || X_probe_location > MAX_PROBE_X) {
  3483. out_of_range_error(PSTR("X"));
  3484. return;
  3485. }
  3486. #endif
  3487. }
  3488. if (code_seen('Y')) {
  3489. Y_probe_location = code_value();
  3490. #if DISABLED(DELTA)
  3491. if (Y_probe_location < MIN_PROBE_Y || Y_probe_location > MAX_PROBE_Y) {
  3492. out_of_range_error(PSTR("Y"));
  3493. return;
  3494. }
  3495. #endif
  3496. }
  3497. #if ENABLED(DELTA)
  3498. if (sqrt(X_probe_location * X_probe_location + Y_probe_location * Y_probe_location) > DELTA_PROBEABLE_RADIUS) {
  3499. SERIAL_PROTOCOLPGM("? (X,Y) location outside of probeable radius.\n");
  3500. return;
  3501. }
  3502. #endif
  3503. bool seen_L = code_seen('L');
  3504. if (seen_L) {
  3505. n_legs = code_value_short();
  3506. if (n_legs < 0 || n_legs > 15) {
  3507. SERIAL_PROTOCOLPGM("?Number of legs in movement not plausible (0-15).\n");
  3508. return;
  3509. }
  3510. if (n_legs == 1) n_legs = 2;
  3511. }
  3512. if (code_seen('S')) {
  3513. schizoid_flag++;
  3514. if (!seen_L) n_legs = 7;
  3515. }
  3516. /**
  3517. * Now get everything to the specified probe point So we can safely do a
  3518. * probe to get us close to the bed. If the Z-Axis is far from the bed,
  3519. * we don't want to use that as a starting point for each probe.
  3520. */
  3521. if (verbose_level > 2)
  3522. SERIAL_PROTOCOLPGM("Positioning the probe...\n");
  3523. #if ENABLED(DELTA)
  3524. // we don't do bed level correction in M48 because we want the raw data when we probe
  3525. reset_bed_level();
  3526. #else
  3527. // we don't do bed level correction in M48 because we want the raw data when we probe
  3528. planner.bed_level_matrix.set_to_identity();
  3529. #endif
  3530. if (Z_start_location < Z_RAISE_BEFORE_PROBING * 2.0)
  3531. do_blocking_move_to_z(Z_start_location);
  3532. do_blocking_move_to_xy(X_probe_location - (X_PROBE_OFFSET_FROM_EXTRUDER), Y_probe_location - (Y_PROBE_OFFSET_FROM_EXTRUDER));
  3533. /**
  3534. * OK, do the initial probe to get us close to the bed.
  3535. * Then retrace the right amount and use that in subsequent probes
  3536. */
  3537. setup_for_endstop_move();
  3538. probe_pt(X_probe_location, Y_probe_location, Z_RAISE_BEFORE_PROBING,
  3539. deploy_probe_for_each_reading ? ProbeDeployAndStow : ProbeDeploy,
  3540. verbose_level);
  3541. raise_z_after_probing();
  3542. for (uint8_t n = 0; n < n_samples; n++) {
  3543. randomSeed(millis());
  3544. delay(500);
  3545. if (n_legs) {
  3546. float radius, angle = random(0.0, 360.0);
  3547. int dir = (random(0, 10) > 5.0) ? -1 : 1; // clockwise or counter clockwise
  3548. radius = random(
  3549. #if ENABLED(DELTA)
  3550. DELTA_PROBEABLE_RADIUS / 8, DELTA_PROBEABLE_RADIUS / 3
  3551. #else
  3552. 5, X_MAX_LENGTH / 8
  3553. #endif
  3554. );
  3555. if (verbose_level > 3) {
  3556. SERIAL_ECHOPAIR("Starting radius: ", radius);
  3557. SERIAL_ECHOPAIR(" angle: ", angle);
  3558. delay(100);
  3559. if (dir > 0)
  3560. SERIAL_ECHO(" Direction: Counter Clockwise \n");
  3561. else
  3562. SERIAL_ECHO(" Direction: Clockwise \n");
  3563. delay(100);
  3564. }
  3565. for (uint8_t l = 0; l < n_legs - 1; l++) {
  3566. double delta_angle;
  3567. if (schizoid_flag)
  3568. // The points of a 5 point star are 72 degrees apart. We need to
  3569. // skip a point and go to the next one on the star.
  3570. delta_angle = dir * 2.0 * 72.0;
  3571. else
  3572. // If we do this line, we are just trying to move further
  3573. // around the circle.
  3574. delta_angle = dir * (float) random(25, 45);
  3575. angle += delta_angle;
  3576. while (angle > 360.0) // We probably do not need to keep the angle between 0 and 2*PI, but the
  3577. angle -= 360.0; // Arduino documentation says the trig functions should not be given values
  3578. while (angle < 0.0) // outside of this range. It looks like they behave correctly with
  3579. angle += 360.0; // numbers outside of the range, but just to be safe we clamp them.
  3580. X_current = X_probe_location - (X_PROBE_OFFSET_FROM_EXTRUDER) + cos(RADIANS(angle)) * radius;
  3581. Y_current = Y_probe_location - (Y_PROBE_OFFSET_FROM_EXTRUDER) + sin(RADIANS(angle)) * radius;
  3582. #if DISABLED(DELTA)
  3583. X_current = constrain(X_current, X_MIN_POS, X_MAX_POS);
  3584. Y_current = constrain(Y_current, Y_MIN_POS, Y_MAX_POS);
  3585. #else
  3586. // If we have gone out too far, we can do a simple fix and scale the numbers
  3587. // back in closer to the origin.
  3588. while (sqrt(X_current * X_current + Y_current * Y_current) > DELTA_PROBEABLE_RADIUS) {
  3589. X_current /= 1.25;
  3590. Y_current /= 1.25;
  3591. if (verbose_level > 3) {
  3592. SERIAL_ECHOPAIR("Pulling point towards center:", X_current);
  3593. SERIAL_ECHOPAIR(", ", Y_current);
  3594. SERIAL_EOL;
  3595. delay(50);
  3596. }
  3597. }
  3598. #endif
  3599. if (verbose_level > 3) {
  3600. SERIAL_PROTOCOL("Going to:");
  3601. SERIAL_ECHOPAIR("x: ", X_current);
  3602. SERIAL_ECHOPAIR("y: ", Y_current);
  3603. SERIAL_ECHOPAIR(" z: ", current_position[Z_AXIS]);
  3604. SERIAL_EOL;
  3605. delay(55);
  3606. }
  3607. do_blocking_move_to_xy(X_current, Y_current);
  3608. } // n_legs loop
  3609. } // n_legs
  3610. /**
  3611. * We don't really have to do this move, but if we don't we can see a
  3612. * funny shift in the Z Height because the user might not have the
  3613. * Z_RAISE_BEFORE_PROBING height identical to the Z_RAISE_BETWEEN_PROBING
  3614. * height. This gets us back to the probe location at the same height that
  3615. * we have been running around the circle at.
  3616. */
  3617. do_blocking_move_to_xy(X_probe_location - (X_PROBE_OFFSET_FROM_EXTRUDER), Y_probe_location - (Y_PROBE_OFFSET_FROM_EXTRUDER));
  3618. if (deploy_probe_for_each_reading)
  3619. sample_set[n] = probe_pt(X_probe_location, Y_probe_location, Z_RAISE_BEFORE_PROBING, ProbeDeployAndStow, verbose_level);
  3620. else {
  3621. if (n == n_samples - 1)
  3622. sample_set[n] = probe_pt(X_probe_location, Y_probe_location, Z_RAISE_BEFORE_PROBING, ProbeStow, verbose_level); else
  3623. sample_set[n] = probe_pt(X_probe_location, Y_probe_location, Z_RAISE_BEFORE_PROBING, ProbeStay, verbose_level);
  3624. }
  3625. /**
  3626. * Get the current mean for the data points we have so far
  3627. */
  3628. sum = 0.0;
  3629. for (uint8_t j = 0; j <= n; j++) sum += sample_set[j];
  3630. mean = sum / (n + 1);
  3631. /**
  3632. * Now, use that mean to calculate the standard deviation for the
  3633. * data points we have so far
  3634. */
  3635. sum = 0.0;
  3636. for (uint8_t j = 0; j <= n; j++) {
  3637. float ss = sample_set[j] - mean;
  3638. sum += ss * ss;
  3639. }
  3640. sigma = sqrt(sum / (n + 1));
  3641. if (verbose_level > 1) {
  3642. SERIAL_PROTOCOL(n + 1);
  3643. SERIAL_PROTOCOLPGM(" of ");
  3644. SERIAL_PROTOCOL((int)n_samples);
  3645. SERIAL_PROTOCOLPGM(" z: ");
  3646. SERIAL_PROTOCOL_F(current_position[Z_AXIS], 6);
  3647. delay(50);
  3648. if (verbose_level > 2) {
  3649. SERIAL_PROTOCOLPGM(" mean: ");
  3650. SERIAL_PROTOCOL_F(mean, 6);
  3651. SERIAL_PROTOCOLPGM(" sigma: ");
  3652. SERIAL_PROTOCOL_F(sigma, 6);
  3653. }
  3654. }
  3655. if (verbose_level > 0) SERIAL_EOL;
  3656. delay(50);
  3657. do_blocking_move_to_z(current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS);
  3658. } // End of probe loop code
  3659. // raise_z_after_probing();
  3660. if (verbose_level > 0) {
  3661. SERIAL_PROTOCOLPGM("Mean: ");
  3662. SERIAL_PROTOCOL_F(mean, 6);
  3663. SERIAL_EOL;
  3664. delay(25);
  3665. }
  3666. SERIAL_PROTOCOLPGM("Standard Deviation: ");
  3667. SERIAL_PROTOCOL_F(sigma, 6);
  3668. SERIAL_EOL; SERIAL_EOL;
  3669. delay(25);
  3670. clean_up_after_endstop_move();
  3671. report_current_position();
  3672. }
  3673. #endif // AUTO_BED_LEVELING_FEATURE && Z_MIN_PROBE_REPEATABILITY_TEST
  3674. /**
  3675. * M75: Start print timer
  3676. */
  3677. inline void gcode_M75() { print_job_timer.start(); }
  3678. /**
  3679. * M76: Pause print timer
  3680. */
  3681. inline void gcode_M76() { print_job_timer.pause(); }
  3682. /**
  3683. * M77: Stop print timer
  3684. */
  3685. inline void gcode_M77() { print_job_timer.stop(); }
  3686. #if ENABLED(PRINTCOUNTER)
  3687. /*+
  3688. * M78: Show print statistics
  3689. */
  3690. inline void gcode_M78() {
  3691. // "M78 S78" will reset the statistics
  3692. if (code_seen('S') && code_value_short() == 78)
  3693. print_job_timer.initStats();
  3694. else print_job_timer.showStats();
  3695. }
  3696. #endif
  3697. /**
  3698. * M104: Set hot end temperature
  3699. */
  3700. inline void gcode_M104() {
  3701. if (get_target_extruder_from_command(104)) return;
  3702. if (DEBUGGING(DRYRUN)) return;
  3703. if (code_seen('S')) {
  3704. float temp = code_value();
  3705. thermalManager.setTargetHotend(temp, target_extruder);
  3706. #if ENABLED(DUAL_X_CARRIAGE)
  3707. if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && target_extruder == 0)
  3708. thermalManager.setTargetHotend(temp == 0.0 ? 0.0 : temp + duplicate_extruder_temp_offset, 1);
  3709. #endif
  3710. #if ENABLED(PRINTJOB_TIMER_AUTOSTART)
  3711. /**
  3712. * We use half EXTRUDE_MINTEMP here to allow nozzles to be put into hot
  3713. * stand by mode, for instance in a dual extruder setup, without affecting
  3714. * the running print timer.
  3715. */
  3716. if (temp <= (EXTRUDE_MINTEMP)/2) {
  3717. print_job_timer.stop();
  3718. LCD_MESSAGEPGM(WELCOME_MSG);
  3719. }
  3720. /**
  3721. * We do not check if the timer is already running because this check will
  3722. * be done for us inside the Stopwatch::start() method thus a running timer
  3723. * will not restart.
  3724. */
  3725. else print_job_timer.start();
  3726. #endif
  3727. if (temp > thermalManager.degHotend(target_extruder)) LCD_MESSAGEPGM(MSG_HEATING);
  3728. }
  3729. }
  3730. #if HAS_TEMP_HOTEND || HAS_TEMP_BED
  3731. void print_heaterstates() {
  3732. #if HAS_TEMP_HOTEND
  3733. SERIAL_PROTOCOLPGM(" T:");
  3734. SERIAL_PROTOCOL_F(thermalManager.degHotend(target_extruder), 1);
  3735. SERIAL_PROTOCOLPGM(" /");
  3736. SERIAL_PROTOCOL_F(thermalManager.degTargetHotend(target_extruder), 1);
  3737. #endif
  3738. #if HAS_TEMP_BED
  3739. SERIAL_PROTOCOLPGM(" B:");
  3740. SERIAL_PROTOCOL_F(thermalManager.degBed(), 1);
  3741. SERIAL_PROTOCOLPGM(" /");
  3742. SERIAL_PROTOCOL_F(thermalManager.degTargetBed(), 1);
  3743. #endif
  3744. #if EXTRUDERS > 1
  3745. for (int8_t e = 0; e < EXTRUDERS; ++e) {
  3746. SERIAL_PROTOCOLPGM(" T");
  3747. SERIAL_PROTOCOL(e);
  3748. SERIAL_PROTOCOLCHAR(':');
  3749. SERIAL_PROTOCOL_F(thermalManager.degHotend(e), 1);
  3750. SERIAL_PROTOCOLPGM(" /");
  3751. SERIAL_PROTOCOL_F(thermalManager.degTargetHotend(e), 1);
  3752. }
  3753. #endif
  3754. #if HAS_TEMP_BED
  3755. SERIAL_PROTOCOLPGM(" B@:");
  3756. #ifdef BED_WATTS
  3757. SERIAL_PROTOCOL(((BED_WATTS) * thermalManager.getHeaterPower(-1)) / 127);
  3758. SERIAL_PROTOCOLCHAR('W');
  3759. #else
  3760. SERIAL_PROTOCOL(thermalManager.getHeaterPower(-1));
  3761. #endif
  3762. #endif
  3763. SERIAL_PROTOCOLPGM(" @:");
  3764. #ifdef EXTRUDER_WATTS
  3765. SERIAL_PROTOCOL(((EXTRUDER_WATTS) * thermalManager.getHeaterPower(target_extruder)) / 127);
  3766. SERIAL_PROTOCOLCHAR('W');
  3767. #else
  3768. SERIAL_PROTOCOL(thermalManager.getHeaterPower(target_extruder));
  3769. #endif
  3770. #if EXTRUDERS > 1
  3771. for (int8_t e = 0; e < EXTRUDERS; ++e) {
  3772. SERIAL_PROTOCOLPGM(" @");
  3773. SERIAL_PROTOCOL(e);
  3774. SERIAL_PROTOCOLCHAR(':');
  3775. #ifdef EXTRUDER_WATTS
  3776. SERIAL_PROTOCOL(((EXTRUDER_WATTS) * thermalManager.getHeaterPower(e)) / 127);
  3777. SERIAL_PROTOCOLCHAR('W');
  3778. #else
  3779. SERIAL_PROTOCOL(thermalManager.getHeaterPower(e));
  3780. #endif
  3781. }
  3782. #endif
  3783. #if ENABLED(SHOW_TEMP_ADC_VALUES)
  3784. #if HAS_TEMP_BED
  3785. SERIAL_PROTOCOLPGM(" ADC B:");
  3786. SERIAL_PROTOCOL_F(thermalManager.degBed(), 1);
  3787. SERIAL_PROTOCOLPGM("C->");
  3788. SERIAL_PROTOCOL_F(thermalManager.rawBedTemp() / OVERSAMPLENR, 0);
  3789. #endif
  3790. for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
  3791. SERIAL_PROTOCOLPGM(" T");
  3792. SERIAL_PROTOCOL(cur_extruder);
  3793. SERIAL_PROTOCOLCHAR(':');
  3794. SERIAL_PROTOCOL_F(thermalManager.degHotend(cur_extruder), 1);
  3795. SERIAL_PROTOCOLPGM("C->");
  3796. SERIAL_PROTOCOL_F(thermalManager.rawHotendTemp(cur_extruder) / OVERSAMPLENR, 0);
  3797. }
  3798. #endif
  3799. }
  3800. #endif
  3801. /**
  3802. * M105: Read hot end and bed temperature
  3803. */
  3804. inline void gcode_M105() {
  3805. if (get_target_extruder_from_command(105)) return;
  3806. #if HAS_TEMP_HOTEND || HAS_TEMP_BED
  3807. SERIAL_PROTOCOLPGM(MSG_OK);
  3808. print_heaterstates();
  3809. #else // !HAS_TEMP_HOTEND && !HAS_TEMP_BED
  3810. SERIAL_ERROR_START;
  3811. SERIAL_ERRORLNPGM(MSG_ERR_NO_THERMISTORS);
  3812. #endif
  3813. SERIAL_EOL;
  3814. }
  3815. #if FAN_COUNT > 0
  3816. /**
  3817. * M106: Set Fan Speed
  3818. *
  3819. * S<int> Speed between 0-255
  3820. * P<index> Fan index, if more than one fan
  3821. */
  3822. inline void gcode_M106() {
  3823. uint16_t s = code_seen('S') ? code_value_short() : 255,
  3824. p = code_seen('P') ? code_value_short() : 0;
  3825. NOMORE(s, 255);
  3826. if (p < FAN_COUNT) fanSpeeds[p] = s;
  3827. }
  3828. /**
  3829. * M107: Fan Off
  3830. */
  3831. inline void gcode_M107() {
  3832. uint16_t p = code_seen('P') ? code_value_short() : 0;
  3833. if (p < FAN_COUNT) fanSpeeds[p] = 0;
  3834. }
  3835. #endif // FAN_COUNT > 0
  3836. /**
  3837. * M109: Sxxx Wait for extruder(s) to reach temperature. Waits only when heating.
  3838. * Rxxx Wait for extruder(s) to reach temperature. Waits when heating and cooling.
  3839. */
  3840. inline void gcode_M109() {
  3841. if (get_target_extruder_from_command(109)) return;
  3842. if (DEBUGGING(DRYRUN)) return;
  3843. bool no_wait_for_cooling = code_seen('S');
  3844. if (no_wait_for_cooling || code_seen('R')) {
  3845. float temp = code_value();
  3846. thermalManager.setTargetHotend(temp, target_extruder);
  3847. #if ENABLED(DUAL_X_CARRIAGE)
  3848. if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && target_extruder == 0)
  3849. thermalManager.setTargetHotend(temp == 0.0 ? 0.0 : temp + duplicate_extruder_temp_offset, 1);
  3850. #endif
  3851. #if ENABLED(PRINTJOB_TIMER_AUTOSTART)
  3852. /**
  3853. * We use half EXTRUDE_MINTEMP here to allow nozzles to be put into hot
  3854. * stand by mode, for instance in a dual extruder setup, without affecting
  3855. * the running print timer.
  3856. */
  3857. if (temp <= (EXTRUDE_MINTEMP)/2) {
  3858. print_job_timer.stop();
  3859. LCD_MESSAGEPGM(WELCOME_MSG);
  3860. }
  3861. /**
  3862. * We do not check if the timer is already running because this check will
  3863. * be done for us inside the Stopwatch::start() method thus a running timer
  3864. * will not restart.
  3865. */
  3866. else print_job_timer.start();
  3867. #endif
  3868. if (temp > thermalManager.degHotend(target_extruder)) LCD_MESSAGEPGM(MSG_HEATING);
  3869. }
  3870. #if ENABLED(AUTOTEMP)
  3871. planner.autotemp_M109();
  3872. #endif
  3873. #if TEMP_RESIDENCY_TIME > 0
  3874. millis_t residency_start_ms = 0;
  3875. // Loop until the temperature has stabilized
  3876. #define TEMP_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + (TEMP_RESIDENCY_TIME) * 1000UL))
  3877. #else
  3878. // Loop until the temperature is very close target
  3879. #define TEMP_CONDITIONS (wants_to_cool ? thermalManager.isCoolingHotend(target_extruder) : thermalManager.isHeatingHotend(target_extruder))
  3880. #endif //TEMP_RESIDENCY_TIME > 0
  3881. float theTarget = -1;
  3882. bool wants_to_cool;
  3883. cancel_heatup = false;
  3884. millis_t now, next_temp_ms = 0;
  3885. KEEPALIVE_STATE(NOT_BUSY);
  3886. do {
  3887. now = millis();
  3888. if (ELAPSED(now, next_temp_ms)) { //Print temp & remaining time every 1s while waiting
  3889. next_temp_ms = now + 1000UL;
  3890. #if HAS_TEMP_HOTEND || HAS_TEMP_BED
  3891. print_heaterstates();
  3892. #endif
  3893. #if TEMP_RESIDENCY_TIME > 0
  3894. SERIAL_PROTOCOLPGM(" W:");
  3895. if (residency_start_ms) {
  3896. long rem = (((TEMP_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL;
  3897. SERIAL_PROTOCOLLN(rem);
  3898. }
  3899. else {
  3900. SERIAL_PROTOCOLLNPGM("?");
  3901. }
  3902. #else
  3903. SERIAL_EOL;
  3904. #endif
  3905. }
  3906. // Target temperature might be changed during the loop
  3907. if (theTarget != thermalManager.degTargetHotend(target_extruder)) {
  3908. wants_to_cool = thermalManager.isCoolingHotend(target_extruder);
  3909. theTarget = thermalManager.degTargetHotend(target_extruder);
  3910. // Exit if S<lower>, continue if S<higher>, R<lower>, or R<higher>
  3911. if (no_wait_for_cooling && wants_to_cool) break;
  3912. // Prevent a wait-forever situation if R is misused i.e. M109 R0
  3913. // Try to calculate a ballpark safe margin by halving EXTRUDE_MINTEMP
  3914. if (wants_to_cool && theTarget < (EXTRUDE_MINTEMP)/2) break;
  3915. }
  3916. idle();
  3917. refresh_cmd_timeout(); // to prevent stepper_inactive_time from running out
  3918. #if TEMP_RESIDENCY_TIME > 0
  3919. float temp_diff = fabs(theTarget - thermalManager.degHotend(target_extruder));
  3920. if (!residency_start_ms) {
  3921. // Start the TEMP_RESIDENCY_TIME timer when we reach target temp for the first time.
  3922. if (temp_diff < TEMP_WINDOW) residency_start_ms = millis();
  3923. }
  3924. else if (temp_diff > TEMP_HYSTERESIS) {
  3925. // Restart the timer whenever the temperature falls outside the hysteresis.
  3926. residency_start_ms = millis();
  3927. }
  3928. #endif //TEMP_RESIDENCY_TIME > 0
  3929. } while (!cancel_heatup && TEMP_CONDITIONS);
  3930. LCD_MESSAGEPGM(MSG_HEATING_COMPLETE);
  3931. KEEPALIVE_STATE(IN_HANDLER);
  3932. }
  3933. #if HAS_TEMP_BED
  3934. /**
  3935. * M190: Sxxx Wait for bed current temp to reach target temp. Waits only when heating
  3936. * Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
  3937. */
  3938. inline void gcode_M190() {
  3939. if (DEBUGGING(DRYRUN)) return;
  3940. LCD_MESSAGEPGM(MSG_BED_HEATING);
  3941. bool no_wait_for_cooling = code_seen('S');
  3942. if (no_wait_for_cooling || code_seen('R')) thermalManager.setTargetBed(code_value());
  3943. #if TEMP_BED_RESIDENCY_TIME > 0
  3944. millis_t residency_start_ms = 0;
  3945. // Loop until the temperature has stabilized
  3946. #define TEMP_BED_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + (TEMP_BED_RESIDENCY_TIME) * 1000UL))
  3947. #else
  3948. // Loop until the temperature is very close target
  3949. #define TEMP_BED_CONDITIONS (wants_to_cool ? thermalManager.isCoolingBed() : thermalManager.isHeatingBed())
  3950. #endif //TEMP_BED_RESIDENCY_TIME > 0
  3951. float theTarget = -1;
  3952. bool wants_to_cool;
  3953. cancel_heatup = false;
  3954. millis_t now, next_temp_ms = 0;
  3955. KEEPALIVE_STATE(NOT_BUSY);
  3956. do {
  3957. now = millis();
  3958. if (ELAPSED(now, next_temp_ms)) { //Print Temp Reading every 1 second while heating up.
  3959. next_temp_ms = now + 1000UL;
  3960. print_heaterstates();
  3961. #if TEMP_BED_RESIDENCY_TIME > 0
  3962. SERIAL_PROTOCOLPGM(" W:");
  3963. if (residency_start_ms) {
  3964. long rem = (((TEMP_BED_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL;
  3965. SERIAL_PROTOCOLLN(rem);
  3966. }
  3967. else {
  3968. SERIAL_PROTOCOLLNPGM("?");
  3969. }
  3970. #else
  3971. SERIAL_EOL;
  3972. #endif
  3973. }
  3974. // Target temperature might be changed during the loop
  3975. if (theTarget != thermalManager.degTargetBed()) {
  3976. wants_to_cool = thermalManager.isCoolingBed();
  3977. theTarget = thermalManager.degTargetBed();
  3978. // Exit if S<lower>, continue if S<higher>, R<lower>, or R<higher>
  3979. if (no_wait_for_cooling && wants_to_cool) break;
  3980. // Prevent a wait-forever situation if R is misused i.e. M190 R0
  3981. // Simply don't wait to cool a bed under 30C
  3982. if (wants_to_cool && theTarget < 30) break;
  3983. }
  3984. idle();
  3985. refresh_cmd_timeout(); // to prevent stepper_inactive_time from running out
  3986. #if TEMP_BED_RESIDENCY_TIME > 0
  3987. float temp_diff = fabs(theTarget - thermalManager.degBed());
  3988. if (!residency_start_ms) {
  3989. // Start the TEMP_BED_RESIDENCY_TIME timer when we reach target temp for the first time.
  3990. if (temp_diff < TEMP_BED_WINDOW) residency_start_ms = millis();
  3991. }
  3992. else if (temp_diff > TEMP_BED_HYSTERESIS) {
  3993. // Restart the timer whenever the temperature falls outside the hysteresis.
  3994. residency_start_ms = millis();
  3995. }
  3996. #endif //TEMP_BED_RESIDENCY_TIME > 0
  3997. } while (!cancel_heatup && TEMP_BED_CONDITIONS);
  3998. LCD_MESSAGEPGM(MSG_BED_DONE);
  3999. KEEPALIVE_STATE(IN_HANDLER);
  4000. }
  4001. #endif // HAS_TEMP_BED
  4002. /**
  4003. * M110: Set Current Line Number
  4004. */
  4005. inline void gcode_M110() {
  4006. if (code_seen('N')) gcode_N = code_value_long();
  4007. }
  4008. /**
  4009. * M111: Set the debug level
  4010. */
  4011. inline void gcode_M111() {
  4012. marlin_debug_flags = code_seen('S') ? code_value_short() : DEBUG_NONE;
  4013. const static char str_debug_1[] PROGMEM = MSG_DEBUG_ECHO;
  4014. const static char str_debug_2[] PROGMEM = MSG_DEBUG_INFO;
  4015. const static char str_debug_4[] PROGMEM = MSG_DEBUG_ERRORS;
  4016. const static char str_debug_8[] PROGMEM = MSG_DEBUG_DRYRUN;
  4017. const static char str_debug_16[] PROGMEM = MSG_DEBUG_COMMUNICATION;
  4018. #if ENABLED(DEBUG_LEVELING_FEATURE)
  4019. const static char str_debug_32[] PROGMEM = MSG_DEBUG_LEVELING;
  4020. #endif
  4021. const static char* const debug_strings[] PROGMEM = {
  4022. str_debug_1, str_debug_2, str_debug_4, str_debug_8, str_debug_16,
  4023. #if ENABLED(DEBUG_LEVELING_FEATURE)
  4024. str_debug_32
  4025. #endif
  4026. };
  4027. SERIAL_ECHO_START;
  4028. SERIAL_ECHOPGM(MSG_DEBUG_PREFIX);
  4029. if (marlin_debug_flags) {
  4030. uint8_t comma = 0;
  4031. for (uint8_t i = 0; i < COUNT(debug_strings); i++) {
  4032. if (TEST(marlin_debug_flags, i)) {
  4033. if (comma++) SERIAL_CHAR(',');
  4034. serialprintPGM((char*)pgm_read_word(&(debug_strings[i])));
  4035. }
  4036. }
  4037. }
  4038. else {
  4039. SERIAL_ECHOPGM(MSG_DEBUG_OFF);
  4040. }
  4041. SERIAL_EOL;
  4042. }
  4043. /**
  4044. * M112: Emergency Stop
  4045. */
  4046. inline void gcode_M112() { kill(PSTR(MSG_KILLED)); }
  4047. #if ENABLED(HOST_KEEPALIVE_FEATURE)
  4048. /**
  4049. * M113: Get or set Host Keepalive interval (0 to disable)
  4050. *
  4051. * S<seconds> Optional. Set the keepalive interval.
  4052. */
  4053. inline void gcode_M113() {
  4054. if (code_seen('S')) {
  4055. host_keepalive_interval = (uint8_t)code_value_short();
  4056. NOMORE(host_keepalive_interval, 60);
  4057. }
  4058. else {
  4059. SERIAL_ECHO_START;
  4060. SERIAL_ECHOPAIR("M113 S", (unsigned long)host_keepalive_interval);
  4061. SERIAL_EOL;
  4062. }
  4063. }
  4064. #endif
  4065. #if ENABLED(BARICUDA)
  4066. #if HAS_HEATER_1
  4067. /**
  4068. * M126: Heater 1 valve open
  4069. */
  4070. inline void gcode_M126() { baricuda_valve_pressure = code_seen('S') ? constrain(code_value(), 0, 255) : 255; }
  4071. /**
  4072. * M127: Heater 1 valve close
  4073. */
  4074. inline void gcode_M127() { baricuda_valve_pressure = 0; }
  4075. #endif
  4076. #if HAS_HEATER_2
  4077. /**
  4078. * M128: Heater 2 valve open
  4079. */
  4080. inline void gcode_M128() { baricuda_e_to_p_pressure = code_seen('S') ? constrain(code_value(), 0, 255) : 255; }
  4081. /**
  4082. * M129: Heater 2 valve close
  4083. */
  4084. inline void gcode_M129() { baricuda_e_to_p_pressure = 0; }
  4085. #endif
  4086. #endif //BARICUDA
  4087. /**
  4088. * M140: Set bed temperature
  4089. */
  4090. inline void gcode_M140() {
  4091. if (DEBUGGING(DRYRUN)) return;
  4092. if (code_seen('S')) thermalManager.setTargetBed(code_value());
  4093. }
  4094. #if ENABLED(ULTIPANEL)
  4095. /**
  4096. * M145: Set the heatup state for a material in the LCD menu
  4097. * S<material> (0=PLA, 1=ABS)
  4098. * H<hotend temp>
  4099. * B<bed temp>
  4100. * F<fan speed>
  4101. */
  4102. inline void gcode_M145() {
  4103. int8_t material = code_seen('S') ? code_value_short() : 0;
  4104. if (material < 0 || material > 1) {
  4105. SERIAL_ERROR_START;
  4106. SERIAL_ERRORLNPGM(MSG_ERR_MATERIAL_INDEX);
  4107. }
  4108. else {
  4109. int v;
  4110. switch (material) {
  4111. case 0:
  4112. if (code_seen('H')) {
  4113. v = code_value_short();
  4114. plaPreheatHotendTemp = constrain(v, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - 15);
  4115. }
  4116. if (code_seen('F')) {
  4117. v = code_value_short();
  4118. plaPreheatFanSpeed = constrain(v, 0, 255);
  4119. }
  4120. #if TEMP_SENSOR_BED != 0
  4121. if (code_seen('B')) {
  4122. v = code_value_short();
  4123. plaPreheatHPBTemp = constrain(v, BED_MINTEMP, BED_MAXTEMP - 15);
  4124. }
  4125. #endif
  4126. break;
  4127. case 1:
  4128. if (code_seen('H')) {
  4129. v = code_value_short();
  4130. absPreheatHotendTemp = constrain(v, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - 15);
  4131. }
  4132. if (code_seen('F')) {
  4133. v = code_value_short();
  4134. absPreheatFanSpeed = constrain(v, 0, 255);
  4135. }
  4136. #if TEMP_SENSOR_BED != 0
  4137. if (code_seen('B')) {
  4138. v = code_value_short();
  4139. absPreheatHPBTemp = constrain(v, BED_MINTEMP, BED_MAXTEMP - 15);
  4140. }
  4141. #endif
  4142. break;
  4143. }
  4144. }
  4145. }
  4146. #endif
  4147. #if HAS_POWER_SWITCH
  4148. /**
  4149. * M80: Turn on Power Supply
  4150. */
  4151. inline void gcode_M80() {
  4152. OUT_WRITE(PS_ON_PIN, PS_ON_AWAKE); //GND
  4153. /**
  4154. * If you have a switch on suicide pin, this is useful
  4155. * if you want to start another print with suicide feature after
  4156. * a print without suicide...
  4157. */
  4158. #if HAS_SUICIDE
  4159. OUT_WRITE(SUICIDE_PIN, HIGH);
  4160. #endif
  4161. #if ENABLED(ULTIPANEL)
  4162. powersupply = true;
  4163. LCD_MESSAGEPGM(WELCOME_MSG);
  4164. lcd_update();
  4165. #endif
  4166. }
  4167. #endif // HAS_POWER_SWITCH
  4168. /**
  4169. * M81: Turn off Power, including Power Supply, if there is one.
  4170. *
  4171. * This code should ALWAYS be available for EMERGENCY SHUTDOWN!
  4172. */
  4173. inline void gcode_M81() {
  4174. thermalManager.disable_all_heaters();
  4175. stepper.finish_and_disable();
  4176. #if FAN_COUNT > 0
  4177. #if FAN_COUNT > 1
  4178. for (uint8_t i = 0; i < FAN_COUNT; i++) fanSpeeds[i] = 0;
  4179. #else
  4180. fanSpeeds[0] = 0;
  4181. #endif
  4182. #endif
  4183. delay(1000); // Wait 1 second before switching off
  4184. #if HAS_SUICIDE
  4185. stepper.synchronize();
  4186. suicide();
  4187. #elif HAS_POWER_SWITCH
  4188. OUT_WRITE(PS_ON_PIN, PS_ON_ASLEEP);
  4189. #endif
  4190. #if ENABLED(ULTIPANEL)
  4191. #if HAS_POWER_SWITCH
  4192. powersupply = false;
  4193. #endif
  4194. LCD_MESSAGEPGM(MACHINE_NAME " " MSG_OFF ".");
  4195. lcd_update();
  4196. #endif
  4197. }
  4198. /**
  4199. * M82: Set E codes absolute (default)
  4200. */
  4201. inline void gcode_M82() { axis_relative_modes[E_AXIS] = false; }
  4202. /**
  4203. * M83: Set E codes relative while in Absolute Coordinates (G90) mode
  4204. */
  4205. inline void gcode_M83() { axis_relative_modes[E_AXIS] = true; }
  4206. /**
  4207. * M18, M84: Disable all stepper motors
  4208. */
  4209. inline void gcode_M18_M84() {
  4210. if (code_seen('S')) {
  4211. stepper_inactive_time = code_value() * 1000UL;
  4212. }
  4213. else {
  4214. 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])));
  4215. if (all_axis) {
  4216. stepper.finish_and_disable();
  4217. }
  4218. else {
  4219. stepper.synchronize();
  4220. if (code_seen('X')) disable_x();
  4221. if (code_seen('Y')) disable_y();
  4222. if (code_seen('Z')) disable_z();
  4223. #if ((E0_ENABLE_PIN != X_ENABLE_PIN) && (E1_ENABLE_PIN != Y_ENABLE_PIN)) // Only enable on boards that have seperate ENABLE_PINS
  4224. if (code_seen('E')) {
  4225. disable_e0();
  4226. disable_e1();
  4227. disable_e2();
  4228. disable_e3();
  4229. }
  4230. #endif
  4231. }
  4232. }
  4233. }
  4234. /**
  4235. * M85: Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
  4236. */
  4237. inline void gcode_M85() {
  4238. if (code_seen('S')) max_inactive_time = code_value() * 1000UL;
  4239. }
  4240. /**
  4241. * M92: Set axis steps-per-unit for one or more axes, X, Y, Z, and E.
  4242. * (Follows the same syntax as G92)
  4243. */
  4244. inline void gcode_M92() {
  4245. for (int8_t i = 0; i < NUM_AXIS; i++) {
  4246. if (code_seen(axis_codes[i])) {
  4247. if (i == E_AXIS) {
  4248. float value = code_value();
  4249. if (value < 20.0) {
  4250. float factor = planner.axis_steps_per_unit[i] / value; // increase e constants if M92 E14 is given for netfab.
  4251. planner.max_e_jerk *= factor;
  4252. planner.max_feedrate[i] *= factor;
  4253. planner.axis_steps_per_sqr_second[i] *= factor;
  4254. }
  4255. planner.axis_steps_per_unit[i] = value;
  4256. }
  4257. else {
  4258. planner.axis_steps_per_unit[i] = code_value();
  4259. }
  4260. }
  4261. }
  4262. }
  4263. /**
  4264. * Output the current position to serial
  4265. */
  4266. static void report_current_position() {
  4267. SERIAL_PROTOCOLPGM("X:");
  4268. SERIAL_PROTOCOL(current_position[X_AXIS]);
  4269. SERIAL_PROTOCOLPGM(" Y:");
  4270. SERIAL_PROTOCOL(current_position[Y_AXIS]);
  4271. SERIAL_PROTOCOLPGM(" Z:");
  4272. SERIAL_PROTOCOL(current_position[Z_AXIS]);
  4273. SERIAL_PROTOCOLPGM(" E:");
  4274. SERIAL_PROTOCOL(current_position[E_AXIS]);
  4275. stepper.report_positions();
  4276. #if ENABLED(SCARA)
  4277. SERIAL_PROTOCOLPGM("SCARA Theta:");
  4278. SERIAL_PROTOCOL(delta[X_AXIS]);
  4279. SERIAL_PROTOCOLPGM(" Psi+Theta:");
  4280. SERIAL_PROTOCOL(delta[Y_AXIS]);
  4281. SERIAL_EOL;
  4282. SERIAL_PROTOCOLPGM("SCARA Cal - Theta:");
  4283. SERIAL_PROTOCOL(delta[X_AXIS] + home_offset[X_AXIS]);
  4284. SERIAL_PROTOCOLPGM(" Psi+Theta (90):");
  4285. SERIAL_PROTOCOL(delta[Y_AXIS] - delta[X_AXIS] - 90 + home_offset[Y_AXIS]);
  4286. SERIAL_EOL;
  4287. SERIAL_PROTOCOLPGM("SCARA step Cal - Theta:");
  4288. SERIAL_PROTOCOL(delta[X_AXIS] / 90 * planner.axis_steps_per_unit[X_AXIS]);
  4289. SERIAL_PROTOCOLPGM(" Psi+Theta:");
  4290. SERIAL_PROTOCOL((delta[Y_AXIS] - delta[X_AXIS]) / 90 * planner.axis_steps_per_unit[Y_AXIS]);
  4291. SERIAL_EOL; SERIAL_EOL;
  4292. #endif
  4293. }
  4294. /**
  4295. * M114: Output current position to serial port
  4296. */
  4297. inline void gcode_M114() { report_current_position(); }
  4298. /**
  4299. * M115: Capabilities string
  4300. */
  4301. inline void gcode_M115() {
  4302. SERIAL_PROTOCOLPGM(MSG_M115_REPORT);
  4303. }
  4304. /**
  4305. * M117: Set LCD Status Message
  4306. */
  4307. inline void gcode_M117() {
  4308. lcd_setstatus(current_command_args);
  4309. }
  4310. /**
  4311. * M119: Output endstop states to serial output
  4312. */
  4313. inline void gcode_M119() { endstops.M119(); }
  4314. /**
  4315. * M120: Enable endstops and set non-homing endstop state to "enabled"
  4316. */
  4317. inline void gcode_M120() { endstops.enable_globally(true); }
  4318. /**
  4319. * M121: Disable endstops and set non-homing endstop state to "disabled"
  4320. */
  4321. inline void gcode_M121() { endstops.enable_globally(false); }
  4322. #if ENABLED(BLINKM)
  4323. /**
  4324. * M150: Set Status LED Color - Use R-U-B for R-G-B
  4325. */
  4326. inline void gcode_M150() {
  4327. SendColors(
  4328. code_seen('R') ? (byte)code_value_short() : 0,
  4329. code_seen('U') ? (byte)code_value_short() : 0,
  4330. code_seen('B') ? (byte)code_value_short() : 0
  4331. );
  4332. }
  4333. #endif // BLINKM
  4334. #if ENABLED(EXPERIMENTAL_I2CBUS)
  4335. /**
  4336. * M155: Send data to a I2C slave device
  4337. *
  4338. * This is a PoC, the formating and arguments for the GCODE will
  4339. * change to be more compatible, the current proposal is:
  4340. *
  4341. * M155 A<slave device address base 10> ; Sets the I2C slave address the data will be sent to
  4342. *
  4343. * M155 B<byte-1 value in base 10>
  4344. * M155 B<byte-2 value in base 10>
  4345. * M155 B<byte-3 value in base 10>
  4346. *
  4347. * M155 S1 ; Send the buffered data and reset the buffer
  4348. * M155 R1 ; Reset the buffer without sending data
  4349. *
  4350. */
  4351. inline void gcode_M155() {
  4352. // Set the target address
  4353. if (code_seen('A'))
  4354. i2c.address((uint8_t) code_value_short());
  4355. // Add a new byte to the buffer
  4356. else if (code_seen('B'))
  4357. i2c.addbyte((int) code_value_short());
  4358. // Flush the buffer to the bus
  4359. else if (code_seen('S')) i2c.send();
  4360. // Reset and rewind the buffer
  4361. else if (code_seen('R')) i2c.reset();
  4362. }
  4363. /**
  4364. * M156: Request X bytes from I2C slave device
  4365. *
  4366. * Usage: M156 A<slave device address base 10> B<number of bytes>
  4367. */
  4368. inline void gcode_M156() {
  4369. uint8_t addr = code_seen('A') ? code_value_short() : 0;
  4370. int bytes = code_seen('B') ? code_value_short() : 1;
  4371. if (addr && bytes > 0 && bytes <= 32) {
  4372. i2c.address(addr);
  4373. i2c.reqbytes(bytes);
  4374. }
  4375. else {
  4376. SERIAL_ERROR_START;
  4377. SERIAL_ERRORLN("Bad i2c request");
  4378. }
  4379. }
  4380. #endif //EXPERIMENTAL_I2CBUS
  4381. /**
  4382. * M200: Set filament diameter and set E axis units to cubic millimeters
  4383. *
  4384. * T<extruder> - Optional extruder number. Current extruder if omitted.
  4385. * D<mm> - Diameter of the filament. Use "D0" to set units back to millimeters.
  4386. */
  4387. inline void gcode_M200() {
  4388. if (get_target_extruder_from_command(200)) return;
  4389. if (code_seen('D')) {
  4390. float diameter = code_value();
  4391. // setting any extruder filament size disables volumetric on the assumption that
  4392. // slicers either generate in extruder values as cubic mm or as as filament feeds
  4393. // for all extruders
  4394. volumetric_enabled = (diameter != 0.0);
  4395. if (volumetric_enabled) {
  4396. filament_size[target_extruder] = diameter;
  4397. // make sure all extruders have some sane value for the filament size
  4398. for (int i = 0; i < EXTRUDERS; i++)
  4399. if (! filament_size[i]) filament_size[i] = DEFAULT_NOMINAL_FILAMENT_DIA;
  4400. }
  4401. }
  4402. else {
  4403. //reserved for setting filament diameter via UFID or filament measuring device
  4404. return;
  4405. }
  4406. calculate_volumetric_multipliers();
  4407. }
  4408. /**
  4409. * M201: Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
  4410. */
  4411. inline void gcode_M201() {
  4412. for (int8_t i = 0; i < NUM_AXIS; i++) {
  4413. if (code_seen(axis_codes[i])) {
  4414. planner.max_acceleration_units_per_sq_second[i] = code_value();
  4415. }
  4416. }
  4417. // 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)
  4418. planner.reset_acceleration_rates();
  4419. }
  4420. #if 0 // Not used for Sprinter/grbl gen6
  4421. inline void gcode_M202() {
  4422. for (int8_t i = 0; i < NUM_AXIS; i++) {
  4423. if (code_seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = code_value() * planner.axis_steps_per_unit[i];
  4424. }
  4425. }
  4426. #endif
  4427. /**
  4428. * M203: Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
  4429. */
  4430. inline void gcode_M203() {
  4431. for (int8_t i = 0; i < NUM_AXIS; i++) {
  4432. if (code_seen(axis_codes[i])) {
  4433. planner.max_feedrate[i] = code_value();
  4434. }
  4435. }
  4436. }
  4437. /**
  4438. * M204: Set Accelerations in mm/sec^2 (M204 P1200 R3000 T3000)
  4439. *
  4440. * P = Printing moves
  4441. * R = Retract only (no X, Y, Z) moves
  4442. * T = Travel (non printing) moves
  4443. *
  4444. * Also sets minimum segment time in ms (B20000) to prevent buffer under-runs and M20 minimum feedrate
  4445. */
  4446. inline void gcode_M204() {
  4447. if (code_seen('S')) { // Kept for legacy compatibility. Should NOT BE USED for new developments.
  4448. planner.travel_acceleration = planner.acceleration = code_value();
  4449. SERIAL_ECHOPAIR("Setting Print and Travel Acceleration: ", planner.acceleration);
  4450. SERIAL_EOL;
  4451. }
  4452. if (code_seen('P')) {
  4453. planner.acceleration = code_value();
  4454. SERIAL_ECHOPAIR("Setting Print Acceleration: ", planner.acceleration);
  4455. SERIAL_EOL;
  4456. }
  4457. if (code_seen('R')) {
  4458. planner.retract_acceleration = code_value();
  4459. SERIAL_ECHOPAIR("Setting Retract Acceleration: ", planner.retract_acceleration);
  4460. SERIAL_EOL;
  4461. }
  4462. if (code_seen('T')) {
  4463. planner.travel_acceleration = code_value();
  4464. SERIAL_ECHOPAIR("Setting Travel Acceleration: ", planner.travel_acceleration);
  4465. SERIAL_EOL;
  4466. }
  4467. }
  4468. /**
  4469. * M205: Set Advanced Settings
  4470. *
  4471. * S = Min Feed Rate (mm/s)
  4472. * T = Min Travel Feed Rate (mm/s)
  4473. * B = Min Segment Time (µs)
  4474. * X = Max XY Jerk (mm/s/s)
  4475. * Z = Max Z Jerk (mm/s/s)
  4476. * E = Max E Jerk (mm/s/s)
  4477. */
  4478. inline void gcode_M205() {
  4479. if (code_seen('S')) planner.min_feedrate = code_value();
  4480. if (code_seen('T')) planner.min_travel_feedrate = code_value();
  4481. if (code_seen('B')) planner.min_segment_time = code_value();
  4482. if (code_seen('X')) planner.max_xy_jerk = code_value();
  4483. if (code_seen('Z')) planner.max_z_jerk = code_value();
  4484. if (code_seen('E')) planner.max_e_jerk = code_value();
  4485. }
  4486. /**
  4487. * M206: Set Additional Homing Offset (X Y Z). SCARA aliases T=X, P=Y
  4488. */
  4489. inline void gcode_M206() {
  4490. for (int8_t i = X_AXIS; i <= Z_AXIS; i++)
  4491. if (code_seen(axis_codes[i]))
  4492. set_home_offset((AxisEnum)i, code_value());
  4493. #if ENABLED(SCARA)
  4494. if (code_seen('T')) set_home_offset(X_AXIS, code_value()); // Theta
  4495. if (code_seen('P')) set_home_offset(Y_AXIS, code_value()); // Psi
  4496. #endif
  4497. sync_plan_position();
  4498. report_current_position();
  4499. }
  4500. #if ENABLED(DELTA)
  4501. /**
  4502. * M665: Set delta configurations
  4503. *
  4504. * L = diagonal rod
  4505. * R = delta radius
  4506. * S = segments per second
  4507. * A = Alpha (Tower 1) diagonal rod trim
  4508. * B = Beta (Tower 2) diagonal rod trim
  4509. * C = Gamma (Tower 3) diagonal rod trim
  4510. */
  4511. inline void gcode_M665() {
  4512. if (code_seen('L')) delta_diagonal_rod = code_value();
  4513. if (code_seen('R')) delta_radius = code_value();
  4514. if (code_seen('S')) delta_segments_per_second = code_value();
  4515. if (code_seen('A')) delta_diagonal_rod_trim_tower_1 = code_value();
  4516. if (code_seen('B')) delta_diagonal_rod_trim_tower_2 = code_value();
  4517. if (code_seen('C')) delta_diagonal_rod_trim_tower_3 = code_value();
  4518. recalc_delta_settings(delta_radius, delta_diagonal_rod);
  4519. }
  4520. /**
  4521. * M666: Set delta endstop adjustment
  4522. */
  4523. inline void gcode_M666() {
  4524. #if ENABLED(DEBUG_LEVELING_FEATURE)
  4525. if (DEBUGGING(LEVELING)) {
  4526. SERIAL_ECHOLNPGM(">>> gcode_M666");
  4527. }
  4528. #endif
  4529. for (int8_t i = X_AXIS; i <= Z_AXIS; i++) {
  4530. if (code_seen(axis_codes[i])) {
  4531. endstop_adj[i] = code_value();
  4532. #if ENABLED(DEBUG_LEVELING_FEATURE)
  4533. if (DEBUGGING(LEVELING)) {
  4534. SERIAL_ECHOPGM("endstop_adj[");
  4535. SERIAL_ECHO(axis_codes[i]);
  4536. SERIAL_ECHOPAIR("] = ", endstop_adj[i]);
  4537. SERIAL_EOL;
  4538. }
  4539. #endif
  4540. }
  4541. }
  4542. #if ENABLED(DEBUG_LEVELING_FEATURE)
  4543. if (DEBUGGING(LEVELING)) {
  4544. SERIAL_ECHOLNPGM("<<< gcode_M666");
  4545. }
  4546. #endif
  4547. }
  4548. #elif ENABLED(Z_DUAL_ENDSTOPS) // !DELTA && ENABLED(Z_DUAL_ENDSTOPS)
  4549. /**
  4550. * M666: For Z Dual Endstop setup, set z axis offset to the z2 axis.
  4551. */
  4552. inline void gcode_M666() {
  4553. if (code_seen('Z')) z_endstop_adj = code_value();
  4554. SERIAL_ECHOPAIR("Z Endstop Adjustment set to (mm):", z_endstop_adj);
  4555. SERIAL_EOL;
  4556. }
  4557. #endif // !DELTA && Z_DUAL_ENDSTOPS
  4558. #if ENABLED(FWRETRACT)
  4559. /**
  4560. * M207: Set firmware retraction values
  4561. *
  4562. * S[+mm] retract_length
  4563. * W[+mm] retract_length_swap (multi-extruder)
  4564. * F[mm/min] retract_feedrate
  4565. * Z[mm] retract_zlift
  4566. */
  4567. inline void gcode_M207() {
  4568. if (code_seen('S')) retract_length = code_value();
  4569. if (code_seen('F')) retract_feedrate = code_value() / 60;
  4570. if (code_seen('Z')) retract_zlift = code_value();
  4571. #if EXTRUDERS > 1
  4572. if (code_seen('W')) retract_length_swap = code_value();
  4573. #endif
  4574. }
  4575. /**
  4576. * M208: Set firmware un-retraction values
  4577. *
  4578. * S[+mm] retract_recover_length (in addition to M207 S*)
  4579. * W[+mm] retract_recover_length_swap (multi-extruder)
  4580. * F[mm/min] retract_recover_feedrate
  4581. */
  4582. inline void gcode_M208() {
  4583. if (code_seen('S')) retract_recover_length = code_value();
  4584. if (code_seen('F')) retract_recover_feedrate = code_value() / 60;
  4585. #if EXTRUDERS > 1
  4586. if (code_seen('W')) retract_recover_length_swap = code_value();
  4587. #endif
  4588. }
  4589. /**
  4590. * M209: Enable automatic retract (M209 S1)
  4591. * detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction.
  4592. */
  4593. inline void gcode_M209() {
  4594. if (code_seen('S')) {
  4595. int t = code_value_short();
  4596. switch (t) {
  4597. case 0:
  4598. autoretract_enabled = false;
  4599. break;
  4600. case 1:
  4601. autoretract_enabled = true;
  4602. break;
  4603. default:
  4604. unknown_command_error();
  4605. return;
  4606. }
  4607. for (int i = 0; i < EXTRUDERS; i++) retracted[i] = false;
  4608. }
  4609. }
  4610. #endif // FWRETRACT
  4611. #if EXTRUDERS > 1
  4612. /**
  4613. * M218 - set hotend offset (in mm)
  4614. *
  4615. * T<tool>
  4616. * X<xoffset>
  4617. * Y<yoffset>
  4618. * Z<zoffset> - Available with DUAL_X_CARRIAGE
  4619. */
  4620. inline void gcode_M218() {
  4621. if (get_target_extruder_from_command(218)) return;
  4622. if (code_seen('X')) extruder_offset[X_AXIS][target_extruder] = code_value();
  4623. if (code_seen('Y')) extruder_offset[Y_AXIS][target_extruder] = code_value();
  4624. #if ENABLED(DUAL_X_CARRIAGE)
  4625. if (code_seen('Z')) extruder_offset[Z_AXIS][target_extruder] = code_value();
  4626. #endif
  4627. SERIAL_ECHO_START;
  4628. SERIAL_ECHOPGM(MSG_HOTEND_OFFSET);
  4629. for (int e = 0; e < EXTRUDERS; e++) {
  4630. SERIAL_CHAR(' ');
  4631. SERIAL_ECHO(extruder_offset[X_AXIS][e]);
  4632. SERIAL_CHAR(',');
  4633. SERIAL_ECHO(extruder_offset[Y_AXIS][e]);
  4634. #if ENABLED(DUAL_X_CARRIAGE)
  4635. SERIAL_CHAR(',');
  4636. SERIAL_ECHO(extruder_offset[Z_AXIS][e]);
  4637. #endif
  4638. }
  4639. SERIAL_EOL;
  4640. }
  4641. #endif // EXTRUDERS > 1
  4642. /**
  4643. * M220: Set speed percentage factor, aka "Feed Rate" (M220 S95)
  4644. */
  4645. inline void gcode_M220() {
  4646. if (code_seen('S')) feedrate_multiplier = code_value();
  4647. }
  4648. /**
  4649. * M221: Set extrusion percentage (M221 T0 S95)
  4650. */
  4651. inline void gcode_M221() {
  4652. if (code_seen('S')) {
  4653. int sval = code_value();
  4654. if (get_target_extruder_from_command(221)) return;
  4655. extruder_multiplier[target_extruder] = sval;
  4656. }
  4657. }
  4658. /**
  4659. * M226: Wait until the specified pin reaches the state required (M226 P<pin> S<state>)
  4660. */
  4661. inline void gcode_M226() {
  4662. if (code_seen('P')) {
  4663. int pin_number = code_value();
  4664. int pin_state = code_seen('S') ? code_value() : -1; // required pin state - default is inverted
  4665. if (pin_state >= -1 && pin_state <= 1) {
  4666. for (uint8_t i = 0; i < COUNT(sensitive_pins); i++) {
  4667. if (sensitive_pins[i] == pin_number) {
  4668. pin_number = -1;
  4669. break;
  4670. }
  4671. }
  4672. if (pin_number > -1) {
  4673. int target = LOW;
  4674. stepper.synchronize();
  4675. pinMode(pin_number, INPUT);
  4676. switch (pin_state) {
  4677. case 1:
  4678. target = HIGH;
  4679. break;
  4680. case 0:
  4681. target = LOW;
  4682. break;
  4683. case -1:
  4684. target = !digitalRead(pin_number);
  4685. break;
  4686. }
  4687. while (digitalRead(pin_number) != target) idle();
  4688. } // pin_number > -1
  4689. } // pin_state -1 0 1
  4690. } // code_seen('P')
  4691. }
  4692. #if HAS_SERVOS
  4693. /**
  4694. * M280: Get or set servo position. P<index> S<angle>
  4695. */
  4696. inline void gcode_M280() {
  4697. int servo_index = code_seen('P') ? code_value_short() : -1;
  4698. int servo_position = 0;
  4699. if (code_seen('S')) {
  4700. servo_position = code_value_short();
  4701. if (servo_index >= 0 && servo_index < NUM_SERVOS)
  4702. servo[servo_index].move(servo_position);
  4703. else {
  4704. SERIAL_ERROR_START;
  4705. SERIAL_ERROR("Servo ");
  4706. SERIAL_ERROR(servo_index);
  4707. SERIAL_ERRORLN(" out of range");
  4708. }
  4709. }
  4710. else if (servo_index >= 0) {
  4711. SERIAL_ECHO_START;
  4712. SERIAL_ECHO(" Servo ");
  4713. SERIAL_ECHO(servo_index);
  4714. SERIAL_ECHO(": ");
  4715. SERIAL_ECHOLN(servo[servo_index].read());
  4716. }
  4717. }
  4718. #endif // HAS_SERVOS
  4719. #if HAS_BUZZER
  4720. /**
  4721. * M300: Play beep sound S<frequency Hz> P<duration ms>
  4722. */
  4723. inline void gcode_M300() {
  4724. uint16_t beepS = code_seen('S') ? code_value_short() : 110;
  4725. uint32_t beepP = code_seen('P') ? code_value_long() : 1000;
  4726. if (beepP > 5000) beepP = 5000; // limit to 5 seconds
  4727. buzz(beepP, beepS);
  4728. }
  4729. #endif // HAS_BUZZER
  4730. #if ENABLED(PIDTEMP)
  4731. /**
  4732. * M301: Set PID parameters P I D (and optionally C, L)
  4733. *
  4734. * P[float] Kp term
  4735. * I[float] Ki term (unscaled)
  4736. * D[float] Kd term (unscaled)
  4737. *
  4738. * With PID_ADD_EXTRUSION_RATE:
  4739. *
  4740. * C[float] Kc term
  4741. * L[float] LPQ length
  4742. */
  4743. inline void gcode_M301() {
  4744. // multi-extruder PID patch: M301 updates or prints a single extruder's PID values
  4745. // default behaviour (omitting E parameter) is to update for extruder 0 only
  4746. int e = code_seen('E') ? code_value() : 0; // extruder being updated
  4747. if (e < EXTRUDERS) { // catch bad input value
  4748. if (code_seen('P')) PID_PARAM(Kp, e) = code_value();
  4749. if (code_seen('I')) PID_PARAM(Ki, e) = scalePID_i(code_value());
  4750. if (code_seen('D')) PID_PARAM(Kd, e) = scalePID_d(code_value());
  4751. #if ENABLED(PID_ADD_EXTRUSION_RATE)
  4752. if (code_seen('C')) PID_PARAM(Kc, e) = code_value();
  4753. if (code_seen('L')) lpq_len = code_value();
  4754. NOMORE(lpq_len, LPQ_MAX_LEN);
  4755. #endif
  4756. thermalManager.updatePID();
  4757. SERIAL_ECHO_START;
  4758. #if ENABLED(PID_PARAMS_PER_EXTRUDER)
  4759. SERIAL_ECHO(" e:"); // specify extruder in serial output
  4760. SERIAL_ECHO(e);
  4761. #endif // PID_PARAMS_PER_EXTRUDER
  4762. SERIAL_ECHO(" p:");
  4763. SERIAL_ECHO(PID_PARAM(Kp, e));
  4764. SERIAL_ECHO(" i:");
  4765. SERIAL_ECHO(unscalePID_i(PID_PARAM(Ki, e)));
  4766. SERIAL_ECHO(" d:");
  4767. SERIAL_ECHO(unscalePID_d(PID_PARAM(Kd, e)));
  4768. #if ENABLED(PID_ADD_EXTRUSION_RATE)
  4769. SERIAL_ECHO(" c:");
  4770. //Kc does not have scaling applied above, or in resetting defaults
  4771. SERIAL_ECHO(PID_PARAM(Kc, e));
  4772. #endif
  4773. SERIAL_EOL;
  4774. }
  4775. else {
  4776. SERIAL_ERROR_START;
  4777. SERIAL_ERRORLN(MSG_INVALID_EXTRUDER);
  4778. }
  4779. }
  4780. #endif // PIDTEMP
  4781. #if ENABLED(PIDTEMPBED)
  4782. inline void gcode_M304() {
  4783. if (code_seen('P')) thermalManager.bedKp = code_value();
  4784. if (code_seen('I')) thermalManager.bedKi = scalePID_i(code_value());
  4785. if (code_seen('D')) thermalManager.bedKd = scalePID_d(code_value());
  4786. thermalManager.updatePID();
  4787. SERIAL_ECHO_START;
  4788. SERIAL_ECHO(" p:");
  4789. SERIAL_ECHO(thermalManager.bedKp);
  4790. SERIAL_ECHO(" i:");
  4791. SERIAL_ECHO(unscalePID_i(thermalManager.bedKi));
  4792. SERIAL_ECHO(" d:");
  4793. SERIAL_ECHOLN(unscalePID_d(thermalManager.bedKd));
  4794. }
  4795. #endif // PIDTEMPBED
  4796. #if defined(CHDK) || HAS_PHOTOGRAPH
  4797. /**
  4798. * M240: Trigger a camera by emulating a Canon RC-1
  4799. * See http://www.doc-diy.net/photo/rc-1_hacked/
  4800. */
  4801. inline void gcode_M240() {
  4802. #ifdef CHDK
  4803. OUT_WRITE(CHDK, HIGH);
  4804. chdkHigh = millis();
  4805. chdkActive = true;
  4806. #elif HAS_PHOTOGRAPH
  4807. const uint8_t NUM_PULSES = 16;
  4808. const float PULSE_LENGTH = 0.01524;
  4809. for (int i = 0; i < NUM_PULSES; i++) {
  4810. WRITE(PHOTOGRAPH_PIN, HIGH);
  4811. _delay_ms(PULSE_LENGTH);
  4812. WRITE(PHOTOGRAPH_PIN, LOW);
  4813. _delay_ms(PULSE_LENGTH);
  4814. }
  4815. delay(7.33);
  4816. for (int i = 0; i < NUM_PULSES; i++) {
  4817. WRITE(PHOTOGRAPH_PIN, HIGH);
  4818. _delay_ms(PULSE_LENGTH);
  4819. WRITE(PHOTOGRAPH_PIN, LOW);
  4820. _delay_ms(PULSE_LENGTH);
  4821. }
  4822. #endif // !CHDK && HAS_PHOTOGRAPH
  4823. }
  4824. #endif // CHDK || PHOTOGRAPH_PIN
  4825. #if HAS_LCD_CONTRAST
  4826. /**
  4827. * M250: Read and optionally set the LCD contrast
  4828. */
  4829. inline void gcode_M250() {
  4830. if (code_seen('C')) set_lcd_contrast(code_value_short());
  4831. SERIAL_PROTOCOLPGM("lcd contrast value: ");
  4832. SERIAL_PROTOCOL(lcd_contrast);
  4833. SERIAL_EOL;
  4834. }
  4835. #endif // HAS_LCD_CONTRAST
  4836. #if ENABLED(PREVENT_DANGEROUS_EXTRUDE)
  4837. /**
  4838. * M302: Allow cold extrudes, or set the minimum extrude S<temperature>.
  4839. */
  4840. inline void gcode_M302() {
  4841. thermalManager.extrude_min_temp = code_seen('S') ? code_value() : 0;
  4842. }
  4843. #endif // PREVENT_DANGEROUS_EXTRUDE
  4844. /**
  4845. * M303: PID relay autotune
  4846. *
  4847. * S<temperature> sets the target temperature. (default 150C)
  4848. * E<extruder> (-1 for the bed) (default 0)
  4849. * C<cycles>
  4850. * U<bool> with a non-zero value will apply the result to current settings
  4851. */
  4852. inline void gcode_M303() {
  4853. #if HAS_PID_HEATING
  4854. int e = code_seen('E') ? code_value_short() : 0;
  4855. int c = code_seen('C') ? code_value_short() : 5;
  4856. bool u = code_seen('U') && code_value_short() != 0;
  4857. float temp = code_seen('S') ? code_value() : (e < 0 ? 70.0 : 150.0);
  4858. if (e >= 0 && e < EXTRUDERS)
  4859. target_extruder = e;
  4860. KEEPALIVE_STATE(NOT_BUSY); // don't send "busy: processing" messages during autotune output
  4861. thermalManager.PID_autotune(temp, e, c, u);
  4862. KEEPALIVE_STATE(IN_HANDLER);
  4863. #else
  4864. SERIAL_ERROR_START;
  4865. SERIAL_ERRORLNPGM(MSG_ERR_M303_DISABLED);
  4866. #endif
  4867. }
  4868. #if ENABLED(SCARA)
  4869. bool SCARA_move_to_cal(uint8_t delta_x, uint8_t delta_y) {
  4870. //SoftEndsEnabled = false; // Ignore soft endstops during calibration
  4871. //SERIAL_ECHOLN(" Soft endstops disabled ");
  4872. if (IsRunning()) {
  4873. //gcode_get_destination(); // For X Y Z E F
  4874. delta[X_AXIS] = delta_x;
  4875. delta[Y_AXIS] = delta_y;
  4876. calculate_SCARA_forward_Transform(delta);
  4877. destination[X_AXIS] = delta[X_AXIS] / axis_scaling[X_AXIS];
  4878. destination[Y_AXIS] = delta[Y_AXIS] / axis_scaling[Y_AXIS];
  4879. prepare_move();
  4880. //ok_to_send();
  4881. return true;
  4882. }
  4883. return false;
  4884. }
  4885. /**
  4886. * M360: SCARA calibration: Move to cal-position ThetaA (0 deg calibration)
  4887. */
  4888. inline bool gcode_M360() {
  4889. SERIAL_ECHOLN(" Cal: Theta 0 ");
  4890. return SCARA_move_to_cal(0, 120);
  4891. }
  4892. /**
  4893. * M361: SCARA calibration: Move to cal-position ThetaB (90 deg calibration - steps per degree)
  4894. */
  4895. inline bool gcode_M361() {
  4896. SERIAL_ECHOLN(" Cal: Theta 90 ");
  4897. return SCARA_move_to_cal(90, 130);
  4898. }
  4899. /**
  4900. * M362: SCARA calibration: Move to cal-position PsiA (0 deg calibration)
  4901. */
  4902. inline bool gcode_M362() {
  4903. SERIAL_ECHOLN(" Cal: Psi 0 ");
  4904. return SCARA_move_to_cal(60, 180);
  4905. }
  4906. /**
  4907. * M363: SCARA calibration: Move to cal-position PsiB (90 deg calibration - steps per degree)
  4908. */
  4909. inline bool gcode_M363() {
  4910. SERIAL_ECHOLN(" Cal: Psi 90 ");
  4911. return SCARA_move_to_cal(50, 90);
  4912. }
  4913. /**
  4914. * M364: SCARA calibration: Move to cal-position PSIC (90 deg to Theta calibration position)
  4915. */
  4916. inline bool gcode_M364() {
  4917. SERIAL_ECHOLN(" Cal: Theta-Psi 90 ");
  4918. return SCARA_move_to_cal(45, 135);
  4919. }
  4920. /**
  4921. * M365: SCARA calibration: Scaling factor, X, Y, Z axis
  4922. */
  4923. inline void gcode_M365() {
  4924. for (int8_t i = X_AXIS; i <= Z_AXIS; i++) {
  4925. if (code_seen(axis_codes[i])) {
  4926. axis_scaling[i] = code_value();
  4927. }
  4928. }
  4929. }
  4930. #endif // SCARA
  4931. #if ENABLED(EXT_SOLENOID)
  4932. void enable_solenoid(uint8_t num) {
  4933. switch (num) {
  4934. case 0:
  4935. OUT_WRITE(SOL0_PIN, HIGH);
  4936. break;
  4937. #if HAS_SOLENOID_1
  4938. case 1:
  4939. OUT_WRITE(SOL1_PIN, HIGH);
  4940. break;
  4941. #endif
  4942. #if HAS_SOLENOID_2
  4943. case 2:
  4944. OUT_WRITE(SOL2_PIN, HIGH);
  4945. break;
  4946. #endif
  4947. #if HAS_SOLENOID_3
  4948. case 3:
  4949. OUT_WRITE(SOL3_PIN, HIGH);
  4950. break;
  4951. #endif
  4952. default:
  4953. SERIAL_ECHO_START;
  4954. SERIAL_ECHOLNPGM(MSG_INVALID_SOLENOID);
  4955. break;
  4956. }
  4957. }
  4958. void enable_solenoid_on_active_extruder() { enable_solenoid(active_extruder); }
  4959. void disable_all_solenoids() {
  4960. OUT_WRITE(SOL0_PIN, LOW);
  4961. OUT_WRITE(SOL1_PIN, LOW);
  4962. OUT_WRITE(SOL2_PIN, LOW);
  4963. OUT_WRITE(SOL3_PIN, LOW);
  4964. }
  4965. /**
  4966. * M380: Enable solenoid on the active extruder
  4967. */
  4968. inline void gcode_M380() { enable_solenoid_on_active_extruder(); }
  4969. /**
  4970. * M381: Disable all solenoids
  4971. */
  4972. inline void gcode_M381() { disable_all_solenoids(); }
  4973. #endif // EXT_SOLENOID
  4974. /**
  4975. * M400: Finish all moves
  4976. */
  4977. inline void gcode_M400() { stepper.synchronize(); }
  4978. #if ENABLED(AUTO_BED_LEVELING_FEATURE) && DISABLED(Z_PROBE_SLED) && (ENABLED(HAS_SERVO_ENDSTOPS) || ENABLED(Z_PROBE_ALLEN_KEY))
  4979. /**
  4980. * M401: Engage Z Servo endstop if available
  4981. */
  4982. inline void gcode_M401() {
  4983. #if ENABLED(HAS_SERVO_ENDSTOPS)
  4984. raise_z_for_servo();
  4985. #endif
  4986. deploy_z_probe();
  4987. }
  4988. /**
  4989. * M402: Retract Z Servo endstop if enabled
  4990. */
  4991. inline void gcode_M402() {
  4992. #if ENABLED(HAS_SERVO_ENDSTOPS)
  4993. raise_z_for_servo();
  4994. #endif
  4995. stow_z_probe(false);
  4996. }
  4997. #endif // AUTO_BED_LEVELING_FEATURE && (ENABLED(HAS_SERVO_ENDSTOPS) || Z_PROBE_ALLEN_KEY) && !Z_PROBE_SLED
  4998. #if ENABLED(FILAMENT_WIDTH_SENSOR)
  4999. /**
  5000. * M404: Display or set the nominal filament width (3mm, 1.75mm ) W<3.0>
  5001. */
  5002. inline void gcode_M404() {
  5003. if (code_seen('W')) {
  5004. filament_width_nominal = code_value();
  5005. }
  5006. else {
  5007. SERIAL_PROTOCOLPGM("Filament dia (nominal mm):");
  5008. SERIAL_PROTOCOLLN(filament_width_nominal);
  5009. }
  5010. }
  5011. /**
  5012. * M405: Turn on filament sensor for control
  5013. */
  5014. inline void gcode_M405() {
  5015. if (code_seen('D')) meas_delay_cm = code_value();
  5016. NOMORE(meas_delay_cm, MAX_MEASUREMENT_DELAY);
  5017. if (filwidth_delay_index2 == -1) { // Initialize the ring buffer if not done since startup
  5018. int temp_ratio = thermalManager.widthFil_to_size_ratio();
  5019. for (uint8_t i = 0; i < COUNT(measurement_delay); ++i)
  5020. measurement_delay[i] = temp_ratio - 100; // Subtract 100 to scale within a signed byte
  5021. filwidth_delay_index1 = filwidth_delay_index2 = 0;
  5022. }
  5023. filament_sensor = true;
  5024. //SERIAL_PROTOCOLPGM("Filament dia (measured mm):");
  5025. //SERIAL_PROTOCOL(filament_width_meas);
  5026. //SERIAL_PROTOCOLPGM("Extrusion ratio(%):");
  5027. //SERIAL_PROTOCOL(extruder_multiplier[active_extruder]);
  5028. }
  5029. /**
  5030. * M406: Turn off filament sensor for control
  5031. */
  5032. inline void gcode_M406() { filament_sensor = false; }
  5033. /**
  5034. * M407: Get measured filament diameter on serial output
  5035. */
  5036. inline void gcode_M407() {
  5037. SERIAL_PROTOCOLPGM("Filament dia (measured mm):");
  5038. SERIAL_PROTOCOLLN(filament_width_meas);
  5039. }
  5040. #endif // FILAMENT_WIDTH_SENSOR
  5041. #if DISABLED(DELTA) && DISABLED(SCARA)
  5042. void set_current_position_from_planner() {
  5043. stepper.synchronize();
  5044. #if ENABLED(AUTO_BED_LEVELING_FEATURE)
  5045. vector_3 pos = planner.adjusted_position(); // values directly from steppers...
  5046. current_position[X_AXIS] = pos.x;
  5047. current_position[Y_AXIS] = pos.y;
  5048. current_position[Z_AXIS] = pos.z;
  5049. #else
  5050. current_position[X_AXIS] = stepper.get_axis_position_mm(X_AXIS);
  5051. current_position[Y_AXIS] = stepper.get_axis_position_mm(Y_AXIS);
  5052. current_position[Z_AXIS] = stepper.get_axis_position_mm(Z_AXIS);
  5053. #endif
  5054. sync_plan_position(); // ...re-apply to planner position
  5055. }
  5056. #endif
  5057. /**
  5058. * M410: Quickstop - Abort all planned moves
  5059. *
  5060. * This will stop the carriages mid-move, so most likely they
  5061. * will be out of sync with the stepper position after this.
  5062. */
  5063. inline void gcode_M410() {
  5064. stepper.quick_stop();
  5065. #if DISABLED(DELTA) && DISABLED(SCARA)
  5066. set_current_position_from_planner();
  5067. #endif
  5068. }
  5069. #if ENABLED(MESH_BED_LEVELING)
  5070. /**
  5071. * M420: Enable/Disable Mesh Bed Leveling
  5072. */
  5073. inline void gcode_M420() { if (code_seen('S') && code_has_value()) mbl.set_has_mesh(!!code_value_short()); }
  5074. /**
  5075. * M421: Set a single Mesh Bed Leveling Z coordinate
  5076. * Use either 'M421 X<mm> Y<mm> Z<mm>' or 'M421 I<xindex> J<yindex> Z<mm>'
  5077. */
  5078. inline void gcode_M421() {
  5079. int8_t px, py;
  5080. float z = 0;
  5081. bool hasX, hasY, hasZ, hasI, hasJ;
  5082. if ((hasX = code_seen('X'))) px = mbl.probe_index_x(code_value());
  5083. if ((hasY = code_seen('Y'))) py = mbl.probe_index_y(code_value());
  5084. if ((hasI = code_seen('I'))) px = code_value();
  5085. if ((hasJ = code_seen('J'))) py = code_value();
  5086. if ((hasZ = code_seen('Z'))) z = code_value();
  5087. if (hasX && hasY && hasZ) {
  5088. if (px >= 0 && py >= 0)
  5089. mbl.set_z(px, py, z);
  5090. else {
  5091. SERIAL_ERROR_START;
  5092. SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY);
  5093. }
  5094. }
  5095. else if (hasI && hasJ && hasZ) {
  5096. if (px >= 0 && px < MESH_NUM_X_POINTS && py >= 0 && py < MESH_NUM_Y_POINTS)
  5097. mbl.set_z(px, py, z);
  5098. else {
  5099. SERIAL_ERROR_START;
  5100. SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY);
  5101. }
  5102. }
  5103. else {
  5104. SERIAL_ERROR_START;
  5105. SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS);
  5106. }
  5107. }
  5108. #endif
  5109. /**
  5110. * M428: Set home_offset based on the distance between the
  5111. * current_position and the nearest "reference point."
  5112. * If an axis is past center its endstop position
  5113. * is the reference-point. Otherwise it uses 0. This allows
  5114. * the Z offset to be set near the bed when using a max endstop.
  5115. *
  5116. * M428 can't be used more than 2cm away from 0 or an endstop.
  5117. *
  5118. * Use M206 to set these values directly.
  5119. */
  5120. inline void gcode_M428() {
  5121. bool err = false;
  5122. for (int8_t i = X_AXIS; i <= Z_AXIS; i++) {
  5123. if (axis_homed[i]) {
  5124. float base = (current_position[i] > (sw_endstop_min[i] + sw_endstop_max[i]) / 2) ? base_home_pos(i) : 0,
  5125. diff = current_position[i] - base;
  5126. if (diff > -20 && diff < 20) {
  5127. set_home_offset((AxisEnum)i, home_offset[i] - diff);
  5128. }
  5129. else {
  5130. SERIAL_ERROR_START;
  5131. SERIAL_ERRORLNPGM(MSG_ERR_M428_TOO_FAR);
  5132. LCD_ALERTMESSAGEPGM("Err: Too far!");
  5133. #if HAS_BUZZER
  5134. buzz(200, 40);
  5135. #endif
  5136. err = true;
  5137. break;
  5138. }
  5139. }
  5140. }
  5141. if (!err) {
  5142. #if ENABLED(DELTA) && ENABLED(SCARA)
  5143. sync_plan_position_delta();
  5144. #else
  5145. sync_plan_position();
  5146. #endif
  5147. report_current_position();
  5148. LCD_MESSAGEPGM(MSG_HOME_OFFSETS_APPLIED);
  5149. #if HAS_BUZZER
  5150. buzz(200, 659);
  5151. buzz(200, 698);
  5152. #endif
  5153. }
  5154. }
  5155. /**
  5156. * M500: Store settings in EEPROM
  5157. */
  5158. inline void gcode_M500() {
  5159. Config_StoreSettings();
  5160. }
  5161. /**
  5162. * M501: Read settings from EEPROM
  5163. */
  5164. inline void gcode_M501() {
  5165. Config_RetrieveSettings();
  5166. }
  5167. /**
  5168. * M502: Revert to default settings
  5169. */
  5170. inline void gcode_M502() {
  5171. Config_ResetDefault();
  5172. }
  5173. /**
  5174. * M503: print settings currently in memory
  5175. */
  5176. inline void gcode_M503() {
  5177. Config_PrintSettings(code_seen('S') && code_value() == 0);
  5178. }
  5179. #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
  5180. /**
  5181. * M540: Set whether SD card print should abort on endstop hit (M540 S<0|1>)
  5182. */
  5183. inline void gcode_M540() {
  5184. if (code_seen('S')) stepper.abort_on_endstop_hit = (code_value() > 0);
  5185. }
  5186. #endif // ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
  5187. #ifdef CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
  5188. inline void gcode_SET_Z_PROBE_OFFSET() {
  5189. SERIAL_ECHO_START;
  5190. SERIAL_ECHOPGM(MSG_ZPROBE_ZOFFSET);
  5191. SERIAL_CHAR(' ');
  5192. if (code_seen('Z')) {
  5193. float value = code_value();
  5194. if (Z_PROBE_OFFSET_RANGE_MIN <= value && value <= Z_PROBE_OFFSET_RANGE_MAX) {
  5195. zprobe_zoffset = value;
  5196. SERIAL_ECHO(zprobe_zoffset);
  5197. }
  5198. else {
  5199. SERIAL_ECHOPGM(MSG_Z_MIN);
  5200. SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MIN);
  5201. SERIAL_ECHOPGM(MSG_Z_MAX);
  5202. SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MAX);
  5203. }
  5204. }
  5205. else {
  5206. SERIAL_ECHOPAIR(": ", zprobe_zoffset);
  5207. }
  5208. SERIAL_EOL;
  5209. }
  5210. #endif // CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
  5211. #if ENABLED(FILAMENTCHANGEENABLE)
  5212. /**
  5213. * M600: Pause for filament change
  5214. *
  5215. * E[distance] - Retract the filament this far (negative value)
  5216. * Z[distance] - Move the Z axis by this distance
  5217. * X[position] - Move to this X position, with Y
  5218. * Y[position] - Move to this Y position, with X
  5219. * L[distance] - Retract distance for removal (manual reload)
  5220. *
  5221. * Default values are used for omitted arguments.
  5222. *
  5223. */
  5224. inline void gcode_M600() {
  5225. if (thermalManager.tooColdToExtrude(active_extruder)) {
  5226. SERIAL_ERROR_START;
  5227. SERIAL_ERRORLNPGM(MSG_TOO_COLD_FOR_M600);
  5228. return;
  5229. }
  5230. float lastpos[NUM_AXIS];
  5231. #if ENABLED(DELTA)
  5232. float fr60 = feedrate / 60;
  5233. #endif
  5234. for (int i = 0; i < NUM_AXIS; i++)
  5235. lastpos[i] = destination[i] = current_position[i];
  5236. #if ENABLED(DELTA)
  5237. #define RUNPLAN calculate_delta(destination); \
  5238. planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], fr60, active_extruder);
  5239. #else
  5240. #define RUNPLAN line_to_destination();
  5241. #endif
  5242. //retract by E
  5243. if (code_seen('E')) destination[E_AXIS] += code_value();
  5244. #ifdef FILAMENTCHANGE_FIRSTRETRACT
  5245. else destination[E_AXIS] += FILAMENTCHANGE_FIRSTRETRACT;
  5246. #endif
  5247. RUNPLAN;
  5248. //lift Z
  5249. if (code_seen('Z')) destination[Z_AXIS] += code_value();
  5250. #ifdef FILAMENTCHANGE_ZADD
  5251. else destination[Z_AXIS] += FILAMENTCHANGE_ZADD;
  5252. #endif
  5253. RUNPLAN;
  5254. //move xy
  5255. if (code_seen('X')) destination[X_AXIS] = code_value();
  5256. #ifdef FILAMENTCHANGE_XPOS
  5257. else destination[X_AXIS] = FILAMENTCHANGE_XPOS;
  5258. #endif
  5259. if (code_seen('Y')) destination[Y_AXIS] = code_value();
  5260. #ifdef FILAMENTCHANGE_YPOS
  5261. else destination[Y_AXIS] = FILAMENTCHANGE_YPOS;
  5262. #endif
  5263. RUNPLAN;
  5264. if (code_seen('L')) destination[E_AXIS] += code_value();
  5265. #ifdef FILAMENTCHANGE_FINALRETRACT
  5266. else destination[E_AXIS] += FILAMENTCHANGE_FINALRETRACT;
  5267. #endif
  5268. RUNPLAN;
  5269. //finish moves
  5270. stepper.synchronize();
  5271. //disable extruder steppers so filament can be removed
  5272. disable_e0();
  5273. disable_e1();
  5274. disable_e2();
  5275. disable_e3();
  5276. delay(100);
  5277. LCD_ALERTMESSAGEPGM(MSG_FILAMENTCHANGE);
  5278. #if DISABLED(AUTO_FILAMENT_CHANGE)
  5279. millis_t next_tick = 0;
  5280. #endif
  5281. KEEPALIVE_STATE(PAUSED_FOR_USER);
  5282. while (!lcd_clicked()) {
  5283. #if DISABLED(AUTO_FILAMENT_CHANGE)
  5284. millis_t ms = millis();
  5285. if (ELAPSED(ms, next_tick)) {
  5286. lcd_quick_feedback();
  5287. next_tick = ms + 2500UL; // feedback every 2.5s while waiting
  5288. }
  5289. idle(true);
  5290. #else
  5291. current_position[E_AXIS] += AUTO_FILAMENT_CHANGE_LENGTH;
  5292. destination[E_AXIS] = current_position[E_AXIS];
  5293. line_to_destination(AUTO_FILAMENT_CHANGE_FEEDRATE);
  5294. stepper.synchronize();
  5295. #endif
  5296. } // while(!lcd_clicked)
  5297. KEEPALIVE_STATE(IN_HANDLER);
  5298. lcd_quick_feedback(); // click sound feedback
  5299. #if ENABLED(AUTO_FILAMENT_CHANGE)
  5300. current_position[E_AXIS] = 0;
  5301. stepper.synchronize();
  5302. #endif
  5303. //return to normal
  5304. if (code_seen('L')) destination[E_AXIS] -= code_value();
  5305. #ifdef FILAMENTCHANGE_FINALRETRACT
  5306. else destination[E_AXIS] -= FILAMENTCHANGE_FINALRETRACT;
  5307. #endif
  5308. current_position[E_AXIS] = destination[E_AXIS]; //the long retract of L is compensated by manual filament feeding
  5309. sync_plan_position_e();
  5310. RUNPLAN; //should do nothing
  5311. lcd_reset_alert_level();
  5312. #if ENABLED(DELTA)
  5313. // Move XYZ to starting position, then E
  5314. calculate_delta(lastpos);
  5315. planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], fr60, active_extruder);
  5316. planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], lastpos[E_AXIS], fr60, active_extruder);
  5317. #else
  5318. // Move XY to starting position, then Z, then E
  5319. destination[X_AXIS] = lastpos[X_AXIS];
  5320. destination[Y_AXIS] = lastpos[Y_AXIS];
  5321. line_to_destination();
  5322. destination[Z_AXIS] = lastpos[Z_AXIS];
  5323. line_to_destination();
  5324. destination[E_AXIS] = lastpos[E_AXIS];
  5325. line_to_destination();
  5326. #endif
  5327. #if ENABLED(FILAMENT_RUNOUT_SENSOR)
  5328. filament_ran_out = false;
  5329. #endif
  5330. }
  5331. #endif // FILAMENTCHANGEENABLE
  5332. #if ENABLED(DUAL_X_CARRIAGE)
  5333. /**
  5334. * M605: Set dual x-carriage movement mode
  5335. *
  5336. * M605 S0: Full control mode. The slicer has full control over x-carriage movement
  5337. * M605 S1: Auto-park mode. The inactive head will auto park/unpark without slicer involvement
  5338. * M605 S2 [Xnnn] [Rmmm]: Duplication mode. The second extruder will duplicate the first with nnn
  5339. * millimeters x-offset and an optional differential hotend temperature of
  5340. * mmm degrees. E.g., with "M605 S2 X100 R2" the second extruder will duplicate
  5341. * the first with a spacing of 100mm in the x direction and 2 degrees hotter.
  5342. *
  5343. * Note: the X axis should be homed after changing dual x-carriage mode.
  5344. */
  5345. inline void gcode_M605() {
  5346. stepper.synchronize();
  5347. if (code_seen('S')) dual_x_carriage_mode = code_value();
  5348. switch (dual_x_carriage_mode) {
  5349. case DXC_DUPLICATION_MODE:
  5350. if (code_seen('X')) duplicate_extruder_x_offset = max(code_value(), X2_MIN_POS - x_home_pos(0));
  5351. if (code_seen('R')) duplicate_extruder_temp_offset = code_value();
  5352. SERIAL_ECHO_START;
  5353. SERIAL_ECHOPGM(MSG_HOTEND_OFFSET);
  5354. SERIAL_CHAR(' ');
  5355. SERIAL_ECHO(extruder_offset[X_AXIS][0]);
  5356. SERIAL_CHAR(',');
  5357. SERIAL_ECHO(extruder_offset[Y_AXIS][0]);
  5358. SERIAL_CHAR(' ');
  5359. SERIAL_ECHO(duplicate_extruder_x_offset);
  5360. SERIAL_CHAR(',');
  5361. SERIAL_ECHOLN(extruder_offset[Y_AXIS][1]);
  5362. break;
  5363. case DXC_FULL_CONTROL_MODE:
  5364. case DXC_AUTO_PARK_MODE:
  5365. break;
  5366. default:
  5367. dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
  5368. break;
  5369. }
  5370. active_extruder_parked = false;
  5371. extruder_duplication_enabled = false;
  5372. delayed_move_time = 0;
  5373. }
  5374. #endif // DUAL_X_CARRIAGE
  5375. /**
  5376. * M907: Set digital trimpot motor current using axis codes X, Y, Z, E, B, S
  5377. */
  5378. inline void gcode_M907() {
  5379. #if HAS_DIGIPOTSS
  5380. for (int i = 0; i < NUM_AXIS; i++)
  5381. if (code_seen(axis_codes[i])) stepper.digipot_current(i, code_value());
  5382. if (code_seen('B')) stepper.digipot_current(4, code_value());
  5383. if (code_seen('S')) for (int i = 0; i <= 4; i++) stepper.digipot_current(i, code_value());
  5384. #endif
  5385. #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
  5386. if (code_seen('X')) stepper.digipot_current(0, code_value());
  5387. #endif
  5388. #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
  5389. if (code_seen('Z')) stepper.digipot_current(1, code_value());
  5390. #endif
  5391. #if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
  5392. if (code_seen('E')) stepper.digipot_current(2, code_value());
  5393. #endif
  5394. #if ENABLED(DIGIPOT_I2C)
  5395. // this one uses actual amps in floating point
  5396. for (int i = 0; i < NUM_AXIS; i++) if (code_seen(axis_codes[i])) digipot_i2c_set_current(i, code_value());
  5397. // for each additional extruder (named B,C,D,E..., channels 4,5,6,7...)
  5398. 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());
  5399. #endif
  5400. #if ENABLED(DAC_STEPPER_CURRENT)
  5401. if (code_seen('S')) {
  5402. float dac_percent = code_value();
  5403. for (uint8_t i = 0; i <= 4; i++) dac_current_percent(i, dac_percent);
  5404. }
  5405. for (uint8_t i = 0; i < NUM_AXIS; i++) if (code_seen(axis_codes[i])) dac_current_percent(i, code_value());
  5406. #endif
  5407. }
  5408. #if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT)
  5409. /**
  5410. * M908: Control digital trimpot directly (M908 P<pin> S<current>)
  5411. */
  5412. inline void gcode_M908() {
  5413. #if HAS_DIGIPOTSS
  5414. stepper.digitalPotWrite(
  5415. code_seen('P') ? code_value() : 0,
  5416. code_seen('S') ? code_value() : 0
  5417. );
  5418. #endif
  5419. #ifdef DAC_STEPPER_CURRENT
  5420. dac_current_raw(
  5421. code_seen('P') ? code_value_long() : -1,
  5422. code_seen('S') ? code_value_short() : 0
  5423. );
  5424. #endif
  5425. }
  5426. #if ENABLED(DAC_STEPPER_CURRENT) // As with Printrbot RevF
  5427. inline void gcode_M909() { dac_print_values(); }
  5428. inline void gcode_M910() { dac_commit_eeprom(); }
  5429. #endif
  5430. #endif // HAS_DIGIPOTSS || DAC_STEPPER_CURRENT
  5431. #if HAS_MICROSTEPS
  5432. // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
  5433. inline void gcode_M350() {
  5434. if (code_seen('S')) for (int i = 0; i <= 4; i++) stepper.microstep_mode(i, code_value());
  5435. for (int i = 0; i < NUM_AXIS; i++) if (code_seen(axis_codes[i])) stepper.microstep_mode(i, (uint8_t)code_value());
  5436. if (code_seen('B')) stepper.microstep_mode(4, code_value());
  5437. stepper.microstep_readings();
  5438. }
  5439. /**
  5440. * M351: Toggle MS1 MS2 pins directly with axis codes X Y Z E B
  5441. * S# determines MS1 or MS2, X# sets the pin high/low.
  5442. */
  5443. inline void gcode_M351() {
  5444. if (code_seen('S')) switch (code_value_short()) {
  5445. case 1:
  5446. for (int i = 0; i < NUM_AXIS; i++) if (code_seen(axis_codes[i])) stepper.microstep_ms(i, code_value(), -1);
  5447. if (code_seen('B')) stepper.microstep_ms(4, code_value(), -1);
  5448. break;
  5449. case 2:
  5450. for (int i = 0; i < NUM_AXIS; i++) if (code_seen(axis_codes[i])) stepper.microstep_ms(i, -1, code_value());
  5451. if (code_seen('B')) stepper.microstep_ms(4, -1, code_value());
  5452. break;
  5453. }
  5454. stepper.microstep_readings();
  5455. }
  5456. #endif // HAS_MICROSTEPS
  5457. /**
  5458. * M999: Restart after being stopped
  5459. *
  5460. * Default behaviour is to flush the serial buffer and request
  5461. * a resend to the host starting on the last N line received.
  5462. *
  5463. * Sending "M999 S1" will resume printing without flushing the
  5464. * existing command buffer.
  5465. *
  5466. */
  5467. inline void gcode_M999() {
  5468. Running = true;
  5469. lcd_reset_alert_level();
  5470. if (code_seen('S') && code_value_short() == 1) return;
  5471. // gcode_LastN = Stopped_gcode_LastN;
  5472. FlushSerialRequestResend();
  5473. }
  5474. /**
  5475. * T0-T3: Switch tool, usually switching extruders
  5476. *
  5477. * F[mm/min] Set the movement feedrate
  5478. */
  5479. inline void gcode_T(uint8_t tmp_extruder) {
  5480. if (tmp_extruder >= EXTRUDERS) {
  5481. SERIAL_ECHO_START;
  5482. SERIAL_CHAR('T');
  5483. SERIAL_PROTOCOL_F(tmp_extruder, DEC);
  5484. SERIAL_ECHOLN(MSG_INVALID_EXTRUDER);
  5485. return;
  5486. }
  5487. float stored_feedrate = feedrate;
  5488. if (code_seen('F')) {
  5489. float next_feedrate = code_value();
  5490. if (next_feedrate > 0.0) stored_feedrate = feedrate = next_feedrate;
  5491. }
  5492. else {
  5493. #ifdef XY_TRAVEL_SPEED
  5494. feedrate = XY_TRAVEL_SPEED;
  5495. #else
  5496. feedrate = min(planner.max_feedrate[X_AXIS], planner.max_feedrate[Y_AXIS]);
  5497. #endif
  5498. }
  5499. #if EXTRUDERS > 1
  5500. if (tmp_extruder != active_extruder) {
  5501. // Save current position to return to after applying extruder offset
  5502. set_destination_to_current();
  5503. #if ENABLED(DUAL_X_CARRIAGE)
  5504. if (dual_x_carriage_mode == DXC_AUTO_PARK_MODE && IsRunning() &&
  5505. (delayed_move_time || current_position[X_AXIS] != x_home_pos(active_extruder))) {
  5506. // Park old head: 1) raise 2) move to park position 3) lower
  5507. planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] + TOOLCHANGE_PARK_ZLIFT,
  5508. current_position[E_AXIS], planner.max_feedrate[Z_AXIS], active_extruder);
  5509. planner.buffer_line(x_home_pos(active_extruder), current_position[Y_AXIS], current_position[Z_AXIS] + TOOLCHANGE_PARK_ZLIFT,
  5510. current_position[E_AXIS], planner.max_feedrate[X_AXIS], active_extruder);
  5511. planner.buffer_line(x_home_pos(active_extruder), current_position[Y_AXIS], current_position[Z_AXIS],
  5512. current_position[E_AXIS], planner.max_feedrate[Z_AXIS], active_extruder);
  5513. stepper.synchronize();
  5514. }
  5515. // apply Y & Z extruder offset (x offset is already used in determining home pos)
  5516. current_position[Y_AXIS] -= extruder_offset[Y_AXIS][active_extruder] - extruder_offset[Y_AXIS][tmp_extruder];
  5517. current_position[Z_AXIS] -= extruder_offset[Z_AXIS][active_extruder] - extruder_offset[Z_AXIS][tmp_extruder];
  5518. active_extruder = tmp_extruder;
  5519. // This function resets the max/min values - the current position may be overwritten below.
  5520. set_axis_is_at_home(X_AXIS);
  5521. if (dual_x_carriage_mode == DXC_FULL_CONTROL_MODE) {
  5522. current_position[X_AXIS] = inactive_extruder_x_pos;
  5523. inactive_extruder_x_pos = destination[X_AXIS];
  5524. }
  5525. else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) {
  5526. active_extruder_parked = (active_extruder == 0); // this triggers the second extruder to move into the duplication position
  5527. if (active_extruder_parked)
  5528. current_position[X_AXIS] = inactive_extruder_x_pos;
  5529. else
  5530. current_position[X_AXIS] = destination[X_AXIS] + duplicate_extruder_x_offset;
  5531. inactive_extruder_x_pos = destination[X_AXIS];
  5532. extruder_duplication_enabled = false;
  5533. }
  5534. else {
  5535. // record raised toolhead position for use by unpark
  5536. memcpy(raised_parked_position, current_position, sizeof(raised_parked_position));
  5537. raised_parked_position[Z_AXIS] += TOOLCHANGE_UNPARK_ZLIFT;
  5538. active_extruder_parked = true;
  5539. delayed_move_time = 0;
  5540. }
  5541. // No extra case for AUTO_BED_LEVELING_FEATURE in DUAL_X_CARRIAGE. Does that mean they don't work together?
  5542. #else // !DUAL_X_CARRIAGE
  5543. #if ENABLED(AUTO_BED_LEVELING_FEATURE)
  5544. // Offset extruder, make sure to apply the bed level rotation matrix
  5545. vector_3 tmp_offset_vec = vector_3(extruder_offset[X_AXIS][tmp_extruder],
  5546. extruder_offset[Y_AXIS][tmp_extruder],
  5547. 0),
  5548. act_offset_vec = vector_3(extruder_offset[X_AXIS][active_extruder],
  5549. extruder_offset[Y_AXIS][active_extruder],
  5550. 0),
  5551. offset_vec = tmp_offset_vec - act_offset_vec;
  5552. #if ENABLED(DEBUG_LEVELING_FEATURE)
  5553. if (DEBUGGING(LEVELING)) {
  5554. SERIAL_ECHOLNPGM(">>> gcode_T");
  5555. tmp_offset_vec.debug("tmp_offset_vec");
  5556. act_offset_vec.debug("act_offset_vec");
  5557. offset_vec.debug("offset_vec (BEFORE)");
  5558. DEBUG_POS("BEFORE rotation", current_position);
  5559. }
  5560. #endif
  5561. offset_vec.apply_rotation(planner.bed_level_matrix.transpose(planner.bed_level_matrix));
  5562. current_position[X_AXIS] += offset_vec.x;
  5563. current_position[Y_AXIS] += offset_vec.y;
  5564. current_position[Z_AXIS] += offset_vec.z;
  5565. #if ENABLED(DEBUG_LEVELING_FEATURE)
  5566. if (DEBUGGING(LEVELING)) {
  5567. offset_vec.debug("offset_vec (AFTER)");
  5568. DEBUG_POS("AFTER rotation", current_position);
  5569. SERIAL_ECHOLNPGM("<<< gcode_T");
  5570. }
  5571. #endif
  5572. #else // !AUTO_BED_LEVELING_FEATURE
  5573. // The newly-selected extruder is actually at...
  5574. for (int i=X_AXIS; i<=Y_AXIS; i++) {
  5575. float diff = extruder_offset[i][tmp_extruder] - extruder_offset[i][active_extruder];
  5576. current_position[i] += diff;
  5577. position_shift[i] += diff; // Offset the coordinate space
  5578. update_software_endstops((AxisEnum)i);
  5579. }
  5580. #endif // !AUTO_BED_LEVELING_FEATURE
  5581. // Set the new active extruder
  5582. active_extruder = tmp_extruder;
  5583. #endif // !DUAL_X_CARRIAGE
  5584. // Tell the planner the new "current position"
  5585. #if ENABLED(DELTA)
  5586. sync_plan_position_delta();
  5587. #else
  5588. sync_plan_position();
  5589. #endif
  5590. // Move to the "old position" (move the extruder into place)
  5591. if (IsRunning()) prepare_move();
  5592. } // (tmp_extruder != active_extruder)
  5593. #if ENABLED(EXT_SOLENOID)
  5594. stepper.synchronize();
  5595. disable_all_solenoids();
  5596. enable_solenoid_on_active_extruder();
  5597. #endif // EXT_SOLENOID
  5598. #endif // EXTRUDERS > 1
  5599. feedrate = stored_feedrate;
  5600. SERIAL_ECHO_START;
  5601. SERIAL_ECHO(MSG_ACTIVE_EXTRUDER);
  5602. SERIAL_PROTOCOLLN((int)active_extruder);
  5603. }
  5604. /**
  5605. * Process a single command and dispatch it to its handler
  5606. * This is called from the main loop()
  5607. */
  5608. void process_next_command() {
  5609. current_command = command_queue[cmd_queue_index_r];
  5610. if (DEBUGGING(ECHO)) {
  5611. SERIAL_ECHO_START;
  5612. SERIAL_ECHOLN(current_command);
  5613. }
  5614. // Sanitize the current command:
  5615. // - Skip leading spaces
  5616. // - Bypass N[-0-9][0-9]*[ ]*
  5617. // - Overwrite * with nul to mark the end
  5618. while (*current_command == ' ') ++current_command;
  5619. if (*current_command == 'N' && NUMERIC_SIGNED(current_command[1])) {
  5620. current_command += 2; // skip N[-0-9]
  5621. while (NUMERIC(*current_command)) ++current_command; // skip [0-9]*
  5622. while (*current_command == ' ') ++current_command; // skip [ ]*
  5623. }
  5624. char* starpos = strchr(current_command, '*'); // * should always be the last parameter
  5625. if (starpos) while (*starpos == ' ' || *starpos == '*') *starpos-- = '\0'; // nullify '*' and ' '
  5626. char *cmd_ptr = current_command;
  5627. // Get the command code, which must be G, M, or T
  5628. char command_code = *cmd_ptr++;
  5629. // Skip spaces to get the numeric part
  5630. while (*cmd_ptr == ' ') cmd_ptr++;
  5631. uint16_t codenum = 0; // define ahead of goto
  5632. // Bail early if there's no code
  5633. bool code_is_good = NUMERIC(*cmd_ptr);
  5634. if (!code_is_good) goto ExitUnknownCommand;
  5635. // Get and skip the code number
  5636. do {
  5637. codenum = (codenum * 10) + (*cmd_ptr - '0');
  5638. cmd_ptr++;
  5639. } while (NUMERIC(*cmd_ptr));
  5640. // Skip all spaces to get to the first argument, or nul
  5641. while (*cmd_ptr == ' ') cmd_ptr++;
  5642. // The command's arguments (if any) start here, for sure!
  5643. current_command_args = cmd_ptr;
  5644. KEEPALIVE_STATE(IN_HANDLER);
  5645. // Handle a known G, M, or T
  5646. switch (command_code) {
  5647. case 'G': switch (codenum) {
  5648. // G0, G1
  5649. case 0:
  5650. case 1:
  5651. gcode_G0_G1();
  5652. break;
  5653. // G2, G3
  5654. #if ENABLED(ARC_SUPPORT) && DISABLED(SCARA)
  5655. case 2: // G2 - CW ARC
  5656. case 3: // G3 - CCW ARC
  5657. gcode_G2_G3(codenum == 2);
  5658. break;
  5659. #endif
  5660. // G4 Dwell
  5661. case 4:
  5662. gcode_G4();
  5663. break;
  5664. #if ENABLED(BEZIER_CURVE_SUPPORT)
  5665. // G5
  5666. case 5: // G5 - Cubic B_spline
  5667. gcode_G5();
  5668. break;
  5669. #endif // BEZIER_CURVE_SUPPORT
  5670. #if ENABLED(FWRETRACT)
  5671. case 10: // G10: retract
  5672. case 11: // G11: retract_recover
  5673. gcode_G10_G11(codenum == 10);
  5674. break;
  5675. #endif // FWRETRACT
  5676. case 28: // G28: Home all axes, one at a time
  5677. gcode_G28();
  5678. break;
  5679. #if ENABLED(AUTO_BED_LEVELING_FEATURE) || ENABLED(MESH_BED_LEVELING)
  5680. case 29: // G29 Detailed Z probe, probes the bed at 3 or more points.
  5681. gcode_G29();
  5682. break;
  5683. #endif
  5684. #if ENABLED(AUTO_BED_LEVELING_FEATURE)
  5685. #if DISABLED(Z_PROBE_SLED)
  5686. case 30: // G30 Single Z probe
  5687. gcode_G30();
  5688. break;
  5689. #else // Z_PROBE_SLED
  5690. case 31: // G31: dock the sled
  5691. case 32: // G32: undock the sled
  5692. dock_sled(codenum == 31);
  5693. break;
  5694. #endif // Z_PROBE_SLED
  5695. #endif // AUTO_BED_LEVELING_FEATURE
  5696. case 90: // G90
  5697. relative_mode = false;
  5698. break;
  5699. case 91: // G91
  5700. relative_mode = true;
  5701. break;
  5702. case 92: // G92
  5703. gcode_G92();
  5704. break;
  5705. }
  5706. break;
  5707. case 'M': switch (codenum) {
  5708. #if ENABLED(ULTIPANEL)
  5709. case 0: // M0 - Unconditional stop - Wait for user button press on LCD
  5710. case 1: // M1 - Conditional stop - Wait for user button press on LCD
  5711. gcode_M0_M1();
  5712. break;
  5713. #endif // ULTIPANEL
  5714. case 17:
  5715. gcode_M17();
  5716. break;
  5717. #if ENABLED(SDSUPPORT)
  5718. case 20: // M20 - list SD card
  5719. gcode_M20(); break;
  5720. case 21: // M21 - init SD card
  5721. gcode_M21(); break;
  5722. case 22: //M22 - release SD card
  5723. gcode_M22(); break;
  5724. case 23: //M23 - Select file
  5725. gcode_M23(); break;
  5726. case 24: //M24 - Start SD print
  5727. gcode_M24(); break;
  5728. case 25: //M25 - Pause SD print
  5729. gcode_M25(); break;
  5730. case 26: //M26 - Set SD index
  5731. gcode_M26(); break;
  5732. case 27: //M27 - Get SD status
  5733. gcode_M27(); break;
  5734. case 28: //M28 - Start SD write
  5735. gcode_M28(); break;
  5736. case 29: //M29 - Stop SD write
  5737. gcode_M29(); break;
  5738. case 30: //M30 <filename> Delete File
  5739. gcode_M30(); break;
  5740. case 32: //M32 - Select file and start SD print
  5741. gcode_M32(); break;
  5742. #if ENABLED(LONG_FILENAME_HOST_SUPPORT)
  5743. case 33: //M33 - Get the long full path to a file or folder
  5744. gcode_M33(); break;
  5745. #endif // LONG_FILENAME_HOST_SUPPORT
  5746. case 928: //M928 - Start SD write
  5747. gcode_M928(); break;
  5748. #endif //SDSUPPORT
  5749. case 31: //M31 take time since the start of the SD print or an M109 command
  5750. gcode_M31();
  5751. break;
  5752. case 42: //M42 -Change pin status via gcode
  5753. gcode_M42();
  5754. break;
  5755. #if ENABLED(AUTO_BED_LEVELING_FEATURE) && ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
  5756. case 48: // M48 Z probe repeatability
  5757. gcode_M48();
  5758. break;
  5759. #endif // AUTO_BED_LEVELING_FEATURE && Z_MIN_PROBE_REPEATABILITY_TEST
  5760. case 75: // Start print timer
  5761. gcode_M75();
  5762. break;
  5763. case 76: // Pause print timer
  5764. gcode_M76();
  5765. break;
  5766. case 77: // Stop print timer
  5767. gcode_M77();
  5768. break;
  5769. #if ENABLED(PRINTCOUNTER)
  5770. case 78: // Show print statistics
  5771. gcode_M78();
  5772. break;
  5773. #endif
  5774. #if ENABLED(M100_FREE_MEMORY_WATCHER)
  5775. case 100:
  5776. gcode_M100();
  5777. break;
  5778. #endif
  5779. case 104: // M104
  5780. gcode_M104();
  5781. break;
  5782. case 110: // M110: Set Current Line Number
  5783. gcode_M110();
  5784. break;
  5785. case 111: // M111: Set debug level
  5786. gcode_M111();
  5787. break;
  5788. case 112: // M112: Emergency Stop
  5789. gcode_M112();
  5790. break;
  5791. #if ENABLED(HOST_KEEPALIVE_FEATURE)
  5792. case 113: // M113: Set Host Keepalive interval
  5793. gcode_M113();
  5794. break;
  5795. #endif
  5796. case 140: // M140: Set bed temp
  5797. gcode_M140();
  5798. break;
  5799. case 105: // M105: Read current temperature
  5800. gcode_M105();
  5801. KEEPALIVE_STATE(NOT_BUSY);
  5802. return; // "ok" already printed
  5803. case 109: // M109: Wait for temperature
  5804. gcode_M109();
  5805. break;
  5806. #if HAS_TEMP_BED
  5807. case 190: // M190: Wait for bed heater to reach target
  5808. gcode_M190();
  5809. break;
  5810. #endif // HAS_TEMP_BED
  5811. #if FAN_COUNT > 0
  5812. case 106: // M106: Fan On
  5813. gcode_M106();
  5814. break;
  5815. case 107: // M107: Fan Off
  5816. gcode_M107();
  5817. break;
  5818. #endif // FAN_COUNT > 0
  5819. #if ENABLED(BARICUDA)
  5820. // PWM for HEATER_1_PIN
  5821. #if HAS_HEATER_1
  5822. case 126: // M126: valve open
  5823. gcode_M126();
  5824. break;
  5825. case 127: // M127: valve closed
  5826. gcode_M127();
  5827. break;
  5828. #endif // HAS_HEATER_1
  5829. // PWM for HEATER_2_PIN
  5830. #if HAS_HEATER_2
  5831. case 128: // M128: valve open
  5832. gcode_M128();
  5833. break;
  5834. case 129: // M129: valve closed
  5835. gcode_M129();
  5836. break;
  5837. #endif // HAS_HEATER_2
  5838. #endif // BARICUDA
  5839. #if HAS_POWER_SWITCH
  5840. case 80: // M80: Turn on Power Supply
  5841. gcode_M80();
  5842. break;
  5843. #endif // HAS_POWER_SWITCH
  5844. case 81: // M81: Turn off Power, including Power Supply, if possible
  5845. gcode_M81();
  5846. break;
  5847. case 82:
  5848. gcode_M82();
  5849. break;
  5850. case 83:
  5851. gcode_M83();
  5852. break;
  5853. case 18: // (for compatibility)
  5854. case 84: // M84
  5855. gcode_M18_M84();
  5856. break;
  5857. case 85: // M85
  5858. gcode_M85();
  5859. break;
  5860. case 92: // M92: Set the steps-per-unit for one or more axes
  5861. gcode_M92();
  5862. break;
  5863. case 115: // M115: Report capabilities
  5864. gcode_M115();
  5865. break;
  5866. case 117: // M117: Set LCD message text, if possible
  5867. gcode_M117();
  5868. break;
  5869. case 114: // M114: Report current position
  5870. gcode_M114();
  5871. break;
  5872. case 120: // M120: Enable endstops
  5873. gcode_M120();
  5874. break;
  5875. case 121: // M121: Disable endstops
  5876. gcode_M121();
  5877. break;
  5878. case 119: // M119: Report endstop states
  5879. gcode_M119();
  5880. break;
  5881. #if ENABLED(ULTIPANEL)
  5882. case 145: // M145: Set material heatup parameters
  5883. gcode_M145();
  5884. break;
  5885. #endif
  5886. #if ENABLED(BLINKM)
  5887. case 150: // M150
  5888. gcode_M150();
  5889. break;
  5890. #endif //BLINKM
  5891. #if ENABLED(EXPERIMENTAL_I2CBUS)
  5892. case 155:
  5893. gcode_M155();
  5894. break;
  5895. case 156:
  5896. gcode_M156();
  5897. break;
  5898. #endif //EXPERIMENTAL_I2CBUS
  5899. case 200: // M200 D<millimeters> set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).
  5900. gcode_M200();
  5901. break;
  5902. case 201: // M201
  5903. gcode_M201();
  5904. break;
  5905. #if 0 // Not used for Sprinter/grbl gen6
  5906. case 202: // M202
  5907. gcode_M202();
  5908. break;
  5909. #endif
  5910. case 203: // M203 max feedrate mm/sec
  5911. gcode_M203();
  5912. break;
  5913. case 204: // M204 acclereration S normal moves T filmanent only moves
  5914. gcode_M204();
  5915. break;
  5916. 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
  5917. gcode_M205();
  5918. break;
  5919. case 206: // M206 additional homing offset
  5920. gcode_M206();
  5921. break;
  5922. #if ENABLED(DELTA)
  5923. case 665: // M665 set delta configurations L<diagonal_rod> R<delta_radius> S<segments_per_sec>
  5924. gcode_M665();
  5925. break;
  5926. #endif
  5927. #if ENABLED(DELTA) || ENABLED(Z_DUAL_ENDSTOPS)
  5928. case 666: // M666 set delta / dual endstop adjustment
  5929. gcode_M666();
  5930. break;
  5931. #endif
  5932. #if ENABLED(FWRETRACT)
  5933. case 207: //M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop]
  5934. gcode_M207();
  5935. break;
  5936. case 208: // M208 - set retract recover length S[positive mm surplus to the M207 S*] F[feedrate mm/min]
  5937. gcode_M208();
  5938. break;
  5939. 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.
  5940. gcode_M209();
  5941. break;
  5942. #endif // FWRETRACT
  5943. #if EXTRUDERS > 1
  5944. case 218: // M218 - set hotend offset (in mm), T<extruder_number> X<offset_on_X> Y<offset_on_Y>
  5945. gcode_M218();
  5946. break;
  5947. #endif
  5948. case 220: // M220 S<factor in percent>- set speed factor override percentage
  5949. gcode_M220();
  5950. break;
  5951. case 221: // M221 S<factor in percent>- set extrude factor override percentage
  5952. gcode_M221();
  5953. break;
  5954. case 226: // M226 P<pin number> S<pin state>- Wait until the specified pin reaches the state required
  5955. gcode_M226();
  5956. break;
  5957. #if HAS_SERVOS
  5958. case 280: // M280 - set servo position absolute. P: servo index, S: angle or microseconds
  5959. gcode_M280();
  5960. break;
  5961. #endif // HAS_SERVOS
  5962. #if HAS_BUZZER
  5963. case 300: // M300 - Play beep tone
  5964. gcode_M300();
  5965. break;
  5966. #endif // HAS_BUZZER
  5967. #if ENABLED(PIDTEMP)
  5968. case 301: // M301
  5969. gcode_M301();
  5970. break;
  5971. #endif // PIDTEMP
  5972. #if ENABLED(PIDTEMPBED)
  5973. case 304: // M304
  5974. gcode_M304();
  5975. break;
  5976. #endif // PIDTEMPBED
  5977. #if defined(CHDK) || HAS_PHOTOGRAPH
  5978. case 240: // M240 Triggers a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/
  5979. gcode_M240();
  5980. break;
  5981. #endif // CHDK || PHOTOGRAPH_PIN
  5982. #if HAS_LCD_CONTRAST
  5983. case 250: // M250 Set LCD contrast value: C<value> (value 0..63)
  5984. gcode_M250();
  5985. break;
  5986. #endif // HAS_LCD_CONTRAST
  5987. #if ENABLED(PREVENT_DANGEROUS_EXTRUDE)
  5988. case 302: // allow cold extrudes, or set the minimum extrude temperature
  5989. gcode_M302();
  5990. break;
  5991. #endif // PREVENT_DANGEROUS_EXTRUDE
  5992. case 303: // M303 PID autotune
  5993. gcode_M303();
  5994. break;
  5995. #if ENABLED(SCARA)
  5996. case 360: // M360 SCARA Theta pos1
  5997. if (gcode_M360()) return;
  5998. break;
  5999. case 361: // M361 SCARA Theta pos2
  6000. if (gcode_M361()) return;
  6001. break;
  6002. case 362: // M362 SCARA Psi pos1
  6003. if (gcode_M362()) return;
  6004. break;
  6005. case 363: // M363 SCARA Psi pos2
  6006. if (gcode_M363()) return;
  6007. break;
  6008. case 364: // M364 SCARA Psi pos3 (90 deg to Theta)
  6009. if (gcode_M364()) return;
  6010. break;
  6011. case 365: // M365 Set SCARA scaling for X Y Z
  6012. gcode_M365();
  6013. break;
  6014. #endif // SCARA
  6015. case 400: // M400 finish all moves
  6016. gcode_M400();
  6017. break;
  6018. #if ENABLED(AUTO_BED_LEVELING_FEATURE) && (ENABLED(HAS_SERVO_ENDSTOPS) || ENABLED(Z_PROBE_ALLEN_KEY)) && DISABLED(Z_PROBE_SLED)
  6019. case 401:
  6020. gcode_M401();
  6021. break;
  6022. case 402:
  6023. gcode_M402();
  6024. break;
  6025. #endif // AUTO_BED_LEVELING_FEATURE && (ENABLED(HAS_SERVO_ENDSTOPS) || Z_PROBE_ALLEN_KEY) && !Z_PROBE_SLED
  6026. #if ENABLED(FILAMENT_WIDTH_SENSOR)
  6027. case 404: //M404 Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or display nominal filament width
  6028. gcode_M404();
  6029. break;
  6030. case 405: //M405 Turn on filament sensor for control
  6031. gcode_M405();
  6032. break;
  6033. case 406: //M406 Turn off filament sensor for control
  6034. gcode_M406();
  6035. break;
  6036. case 407: //M407 Display measured filament diameter
  6037. gcode_M407();
  6038. break;
  6039. #endif // ENABLED(FILAMENT_WIDTH_SENSOR)
  6040. case 410: // M410 quickstop - Abort all the planned moves.
  6041. gcode_M410();
  6042. break;
  6043. #if ENABLED(MESH_BED_LEVELING)
  6044. case 420: // M420 Enable/Disable Mesh Bed Leveling
  6045. gcode_M420();
  6046. break;
  6047. case 421: // M421 Set a Mesh Bed Leveling Z coordinate
  6048. gcode_M421();
  6049. break;
  6050. #endif
  6051. case 428: // M428 Apply current_position to home_offset
  6052. gcode_M428();
  6053. break;
  6054. case 500: // M500 Store settings in EEPROM
  6055. gcode_M500();
  6056. break;
  6057. case 501: // M501 Read settings from EEPROM
  6058. gcode_M501();
  6059. break;
  6060. case 502: // M502 Revert to default settings
  6061. gcode_M502();
  6062. break;
  6063. case 503: // M503 print settings currently in memory
  6064. gcode_M503();
  6065. break;
  6066. #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
  6067. case 540:
  6068. gcode_M540();
  6069. break;
  6070. #endif
  6071. #ifdef CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
  6072. case CUSTOM_M_CODE_SET_Z_PROBE_OFFSET:
  6073. gcode_SET_Z_PROBE_OFFSET();
  6074. break;
  6075. #endif // CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
  6076. #if ENABLED(FILAMENTCHANGEENABLE)
  6077. case 600: //Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
  6078. gcode_M600();
  6079. break;
  6080. #endif // FILAMENTCHANGEENABLE
  6081. #if ENABLED(DUAL_X_CARRIAGE)
  6082. case 605:
  6083. gcode_M605();
  6084. break;
  6085. #endif // DUAL_X_CARRIAGE
  6086. case 907: // M907 Set digital trimpot motor current using axis codes.
  6087. gcode_M907();
  6088. break;
  6089. #if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT)
  6090. case 908: // M908 Control digital trimpot directly.
  6091. gcode_M908();
  6092. break;
  6093. #if ENABLED(DAC_STEPPER_CURRENT) // As with Printrbot RevF
  6094. case 909: // M909 Print digipot/DAC current value
  6095. gcode_M909();
  6096. break;
  6097. case 910: // M910 Commit digipot/DAC value to external EEPROM
  6098. gcode_M910();
  6099. break;
  6100. #endif
  6101. #endif // HAS_DIGIPOTSS || DAC_STEPPER_CURRENT
  6102. #if HAS_MICROSTEPS
  6103. case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
  6104. gcode_M350();
  6105. break;
  6106. case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low.
  6107. gcode_M351();
  6108. break;
  6109. #endif // HAS_MICROSTEPS
  6110. case 999: // M999: Restart after being Stopped
  6111. gcode_M999();
  6112. break;
  6113. }
  6114. break;
  6115. case 'T':
  6116. gcode_T(codenum);
  6117. break;
  6118. default: code_is_good = false;
  6119. }
  6120. KEEPALIVE_STATE(NOT_BUSY);
  6121. ExitUnknownCommand:
  6122. // Still unknown command? Throw an error
  6123. if (!code_is_good) unknown_command_error();
  6124. ok_to_send();
  6125. }
  6126. void FlushSerialRequestResend() {
  6127. //char command_queue[cmd_queue_index_r][100]="Resend:";
  6128. MYSERIAL.flush();
  6129. SERIAL_PROTOCOLPGM(MSG_RESEND);
  6130. SERIAL_PROTOCOLLN(gcode_LastN + 1);
  6131. ok_to_send();
  6132. }
  6133. void ok_to_send() {
  6134. refresh_cmd_timeout();
  6135. if (!send_ok[cmd_queue_index_r]) return;
  6136. SERIAL_PROTOCOLPGM(MSG_OK);
  6137. #if ENABLED(ADVANCED_OK)
  6138. char* p = command_queue[cmd_queue_index_r];
  6139. if (*p == 'N') {
  6140. SERIAL_PROTOCOL(' ');
  6141. SERIAL_ECHO(*p++);
  6142. while (NUMERIC_SIGNED(*p))
  6143. SERIAL_ECHO(*p++);
  6144. }
  6145. SERIAL_PROTOCOLPGM(" P"); SERIAL_PROTOCOL(int(BLOCK_BUFFER_SIZE - planner.movesplanned() - 1));
  6146. SERIAL_PROTOCOLPGM(" B"); SERIAL_PROTOCOL(BUFSIZE - commands_in_queue);
  6147. #endif
  6148. SERIAL_EOL;
  6149. }
  6150. void clamp_to_software_endstops(float target[3]) {
  6151. if (min_software_endstops) {
  6152. NOLESS(target[X_AXIS], sw_endstop_min[X_AXIS]);
  6153. NOLESS(target[Y_AXIS], sw_endstop_min[Y_AXIS]);
  6154. NOLESS(target[Z_AXIS], sw_endstop_min[Z_AXIS]);
  6155. }
  6156. if (max_software_endstops) {
  6157. NOMORE(target[X_AXIS], sw_endstop_max[X_AXIS]);
  6158. NOMORE(target[Y_AXIS], sw_endstop_max[Y_AXIS]);
  6159. NOMORE(target[Z_AXIS], sw_endstop_max[Z_AXIS]);
  6160. }
  6161. }
  6162. #if ENABLED(DELTA)
  6163. void recalc_delta_settings(float radius, float diagonal_rod) {
  6164. delta_tower1_x = -SIN_60 * (radius + DELTA_RADIUS_TRIM_TOWER_1); // front left tower
  6165. delta_tower1_y = -COS_60 * (radius + DELTA_RADIUS_TRIM_TOWER_1);
  6166. delta_tower2_x = SIN_60 * (radius + DELTA_RADIUS_TRIM_TOWER_2); // front right tower
  6167. delta_tower2_y = -COS_60 * (radius + DELTA_RADIUS_TRIM_TOWER_2);
  6168. delta_tower3_x = 0.0; // back middle tower
  6169. delta_tower3_y = (radius + DELTA_RADIUS_TRIM_TOWER_3);
  6170. delta_diagonal_rod_2_tower_1 = sq(diagonal_rod + delta_diagonal_rod_trim_tower_1);
  6171. delta_diagonal_rod_2_tower_2 = sq(diagonal_rod + delta_diagonal_rod_trim_tower_2);
  6172. delta_diagonal_rod_2_tower_3 = sq(diagonal_rod + delta_diagonal_rod_trim_tower_3);
  6173. }
  6174. void calculate_delta(float cartesian[3]) {
  6175. delta[TOWER_1] = sqrt(delta_diagonal_rod_2_tower_1
  6176. - sq(delta_tower1_x - cartesian[X_AXIS])
  6177. - sq(delta_tower1_y - cartesian[Y_AXIS])
  6178. ) + cartesian[Z_AXIS];
  6179. delta[TOWER_2] = sqrt(delta_diagonal_rod_2_tower_2
  6180. - sq(delta_tower2_x - cartesian[X_AXIS])
  6181. - sq(delta_tower2_y - cartesian[Y_AXIS])
  6182. ) + cartesian[Z_AXIS];
  6183. delta[TOWER_3] = sqrt(delta_diagonal_rod_2_tower_3
  6184. - sq(delta_tower3_x - cartesian[X_AXIS])
  6185. - sq(delta_tower3_y - cartesian[Y_AXIS])
  6186. ) + cartesian[Z_AXIS];
  6187. /**
  6188. SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]);
  6189. SERIAL_ECHOPGM(" y="); SERIAL_ECHO(cartesian[Y_AXIS]);
  6190. SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(cartesian[Z_AXIS]);
  6191. SERIAL_ECHOPGM("delta a="); SERIAL_ECHO(delta[TOWER_1]);
  6192. SERIAL_ECHOPGM(" b="); SERIAL_ECHO(delta[TOWER_2]);
  6193. SERIAL_ECHOPGM(" c="); SERIAL_ECHOLN(delta[TOWER_3]);
  6194. */
  6195. }
  6196. #if ENABLED(AUTO_BED_LEVELING_FEATURE)
  6197. // Adjust print surface height by linear interpolation over the bed_level array.
  6198. void adjust_delta(float cartesian[3]) {
  6199. if (delta_grid_spacing[0] == 0 || delta_grid_spacing[1] == 0) return; // G29 not done!
  6200. int half = (AUTO_BED_LEVELING_GRID_POINTS - 1) / 2;
  6201. float h1 = 0.001 - half, h2 = half - 0.001,
  6202. grid_x = max(h1, min(h2, cartesian[X_AXIS] / delta_grid_spacing[0])),
  6203. grid_y = max(h1, min(h2, cartesian[Y_AXIS] / delta_grid_spacing[1]));
  6204. int floor_x = floor(grid_x), floor_y = floor(grid_y);
  6205. float ratio_x = grid_x - floor_x, ratio_y = grid_y - floor_y,
  6206. z1 = bed_level[floor_x + half][floor_y + half],
  6207. z2 = bed_level[floor_x + half][floor_y + half + 1],
  6208. z3 = bed_level[floor_x + half + 1][floor_y + half],
  6209. z4 = bed_level[floor_x + half + 1][floor_y + half + 1],
  6210. left = (1 - ratio_y) * z1 + ratio_y * z2,
  6211. right = (1 - ratio_y) * z3 + ratio_y * z4,
  6212. offset = (1 - ratio_x) * left + ratio_x * right;
  6213. delta[X_AXIS] += offset;
  6214. delta[Y_AXIS] += offset;
  6215. delta[Z_AXIS] += offset;
  6216. /**
  6217. SERIAL_ECHOPGM("grid_x="); SERIAL_ECHO(grid_x);
  6218. SERIAL_ECHOPGM(" grid_y="); SERIAL_ECHO(grid_y);
  6219. SERIAL_ECHOPGM(" floor_x="); SERIAL_ECHO(floor_x);
  6220. SERIAL_ECHOPGM(" floor_y="); SERIAL_ECHO(floor_y);
  6221. SERIAL_ECHOPGM(" ratio_x="); SERIAL_ECHO(ratio_x);
  6222. SERIAL_ECHOPGM(" ratio_y="); SERIAL_ECHO(ratio_y);
  6223. SERIAL_ECHOPGM(" z1="); SERIAL_ECHO(z1);
  6224. SERIAL_ECHOPGM(" z2="); SERIAL_ECHO(z2);
  6225. SERIAL_ECHOPGM(" z3="); SERIAL_ECHO(z3);
  6226. SERIAL_ECHOPGM(" z4="); SERIAL_ECHO(z4);
  6227. SERIAL_ECHOPGM(" left="); SERIAL_ECHO(left);
  6228. SERIAL_ECHOPGM(" right="); SERIAL_ECHO(right);
  6229. SERIAL_ECHOPGM(" offset="); SERIAL_ECHOLN(offset);
  6230. */
  6231. }
  6232. #endif // AUTO_BED_LEVELING_FEATURE
  6233. #endif // DELTA
  6234. #if ENABLED(MESH_BED_LEVELING)
  6235. // This function is used to split lines on mesh borders so each segment is only part of one mesh area
  6236. void mesh_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) {
  6237. if (!mbl.active()) {
  6238. planner.buffer_line(x, y, z, e, feed_rate, extruder);
  6239. set_current_to_destination();
  6240. return;
  6241. }
  6242. int pcx = mbl.cel_index_x(current_position[X_AXIS] - home_offset[X_AXIS]);
  6243. int pcy = mbl.cel_index_y(current_position[Y_AXIS] - home_offset[Y_AXIS]);
  6244. int cx = mbl.cel_index_x(x - home_offset[X_AXIS]);
  6245. int cy = mbl.cel_index_y(y - home_offset[Y_AXIS]);
  6246. NOMORE(pcx, MESH_NUM_X_POINTS - 2);
  6247. NOMORE(pcy, MESH_NUM_Y_POINTS - 2);
  6248. NOMORE(cx, MESH_NUM_X_POINTS - 2);
  6249. NOMORE(cy, MESH_NUM_Y_POINTS - 2);
  6250. if (pcx == cx && pcy == cy) {
  6251. // Start and end on same mesh square
  6252. planner.buffer_line(x, y, z, e, feed_rate, extruder);
  6253. set_current_to_destination();
  6254. return;
  6255. }
  6256. float nx, ny, nz, ne, normalized_dist;
  6257. if (cx > pcx && TEST(x_splits, cx)) {
  6258. nx = mbl.get_probe_x(cx) + home_offset[X_AXIS];
  6259. normalized_dist = (nx - current_position[X_AXIS]) / (x - current_position[X_AXIS]);
  6260. ny = current_position[Y_AXIS] + (y - current_position[Y_AXIS]) * normalized_dist;
  6261. nz = current_position[Z_AXIS] + (z - current_position[Z_AXIS]) * normalized_dist;
  6262. ne = current_position[E_AXIS] + (e - current_position[E_AXIS]) * normalized_dist;
  6263. CBI(x_splits, cx);
  6264. }
  6265. else if (cx < pcx && TEST(x_splits, pcx)) {
  6266. nx = mbl.get_probe_x(pcx) + home_offset[X_AXIS];
  6267. normalized_dist = (nx - current_position[X_AXIS]) / (x - current_position[X_AXIS]);
  6268. ny = current_position[Y_AXIS] + (y - current_position[Y_AXIS]) * normalized_dist;
  6269. nz = current_position[Z_AXIS] + (z - current_position[Z_AXIS]) * normalized_dist;
  6270. ne = current_position[E_AXIS] + (e - current_position[E_AXIS]) * normalized_dist;
  6271. CBI(x_splits, pcx);
  6272. }
  6273. else if (cy > pcy && TEST(y_splits, cy)) {
  6274. ny = mbl.get_probe_y(cy) + home_offset[Y_AXIS];
  6275. normalized_dist = (ny - current_position[Y_AXIS]) / (y - current_position[Y_AXIS]);
  6276. nx = current_position[X_AXIS] + (x - current_position[X_AXIS]) * normalized_dist;
  6277. nz = current_position[Z_AXIS] + (z - current_position[Z_AXIS]) * normalized_dist;
  6278. ne = current_position[E_AXIS] + (e - current_position[E_AXIS]) * normalized_dist;
  6279. CBI(y_splits, cy);
  6280. }
  6281. else if (cy < pcy && TEST(y_splits, pcy)) {
  6282. ny = mbl.get_probe_y(pcy) + home_offset[Y_AXIS];
  6283. normalized_dist = (ny - current_position[Y_AXIS]) / (y - current_position[Y_AXIS]);
  6284. nx = current_position[X_AXIS] + (x - current_position[X_AXIS]) * normalized_dist;
  6285. nz = current_position[Z_AXIS] + (z - current_position[Z_AXIS]) * normalized_dist;
  6286. ne = current_position[E_AXIS] + (e - current_position[E_AXIS]) * normalized_dist;
  6287. CBI(y_splits, pcy);
  6288. }
  6289. else {
  6290. // Already split on a border
  6291. planner.buffer_line(x, y, z, e, feed_rate, extruder);
  6292. set_current_to_destination();
  6293. return;
  6294. }
  6295. // Do the split and look for more borders
  6296. destination[X_AXIS] = nx;
  6297. destination[Y_AXIS] = ny;
  6298. destination[Z_AXIS] = nz;
  6299. destination[E_AXIS] = ne;
  6300. mesh_buffer_line(nx, ny, nz, ne, feed_rate, extruder, x_splits, y_splits);
  6301. destination[X_AXIS] = x;
  6302. destination[Y_AXIS] = y;
  6303. destination[Z_AXIS] = z;
  6304. destination[E_AXIS] = e;
  6305. mesh_buffer_line(x, y, z, e, feed_rate, extruder, x_splits, y_splits);
  6306. }
  6307. #endif // MESH_BED_LEVELING
  6308. #if ENABLED(PREVENT_DANGEROUS_EXTRUDE)
  6309. inline void prevent_dangerous_extrude(float& curr_e, float& dest_e) {
  6310. if (DEBUGGING(DRYRUN)) return;
  6311. float de = dest_e - curr_e;
  6312. if (de) {
  6313. if (thermalManager.tooColdToExtrude(active_extruder)) {
  6314. curr_e = dest_e; // Behave as if the move really took place, but ignore E part
  6315. SERIAL_ECHO_START;
  6316. SERIAL_ECHOLNPGM(MSG_ERR_COLD_EXTRUDE_STOP);
  6317. }
  6318. #if ENABLED(PREVENT_LENGTHY_EXTRUDE)
  6319. if (labs(de) > EXTRUDE_MAXLENGTH) {
  6320. curr_e = dest_e; // Behave as if the move really took place, but ignore E part
  6321. SERIAL_ECHO_START;
  6322. SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP);
  6323. }
  6324. #endif
  6325. }
  6326. }
  6327. #endif // PREVENT_DANGEROUS_EXTRUDE
  6328. #if ENABLED(DELTA) || ENABLED(SCARA)
  6329. inline bool prepare_move_delta(float target[NUM_AXIS]) {
  6330. float difference[NUM_AXIS];
  6331. for (int8_t i = 0; i < NUM_AXIS; i++) difference[i] = target[i] - current_position[i];
  6332. float cartesian_mm = sqrt(sq(difference[X_AXIS]) + sq(difference[Y_AXIS]) + sq(difference[Z_AXIS]));
  6333. if (cartesian_mm < 0.000001) cartesian_mm = abs(difference[E_AXIS]);
  6334. if (cartesian_mm < 0.000001) return false;
  6335. float _feedrate = feedrate * feedrate_multiplier / 6000.0;
  6336. float seconds = cartesian_mm / _feedrate;
  6337. int steps = max(1, int(delta_segments_per_second * seconds));
  6338. float inv_steps = 1.0/steps;
  6339. // SERIAL_ECHOPGM("mm="); SERIAL_ECHO(cartesian_mm);
  6340. // SERIAL_ECHOPGM(" seconds="); SERIAL_ECHO(seconds);
  6341. // SERIAL_ECHOPGM(" steps="); SERIAL_ECHOLN(steps);
  6342. for (int s = 1; s <= steps; s++) {
  6343. float fraction = float(s) * inv_steps;
  6344. for (int8_t i = 0; i < NUM_AXIS; i++)
  6345. target[i] = current_position[i] + difference[i] * fraction;
  6346. calculate_delta(target);
  6347. #if ENABLED(AUTO_BED_LEVELING_FEATURE)
  6348. if (!bed_leveling_in_progress) adjust_delta(target);
  6349. #endif
  6350. //DEBUG_POS("prepare_move_delta", target);
  6351. //DEBUG_POS("prepare_move_delta", delta);
  6352. planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], target[E_AXIS], _feedrate, active_extruder);
  6353. }
  6354. return true;
  6355. }
  6356. #endif // DELTA || SCARA
  6357. #if ENABLED(SCARA)
  6358. inline bool prepare_move_scara(float target[NUM_AXIS]) { return prepare_move_delta(target); }
  6359. #endif
  6360. #if ENABLED(DUAL_X_CARRIAGE)
  6361. inline bool prepare_move_dual_x_carriage() {
  6362. if (active_extruder_parked) {
  6363. if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && active_extruder == 0) {
  6364. // move duplicate extruder into correct duplication position.
  6365. planner.set_position_mm(inactive_extruder_x_pos, current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  6366. planner.buffer_line(current_position[X_AXIS] + duplicate_extruder_x_offset,
  6367. current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], planner.max_feedrate[X_AXIS], 1);
  6368. sync_plan_position();
  6369. stepper.synchronize();
  6370. extruder_duplication_enabled = true;
  6371. active_extruder_parked = false;
  6372. }
  6373. else if (dual_x_carriage_mode == DXC_AUTO_PARK_MODE) { // handle unparking of head
  6374. if (current_position[E_AXIS] == destination[E_AXIS]) {
  6375. // This is a travel move (with no extrusion)
  6376. // Skip it, but keep track of the current position
  6377. // (so it can be used as the start of the next non-travel move)
  6378. if (delayed_move_time != 0xFFFFFFFFUL) {
  6379. set_current_to_destination();
  6380. NOLESS(raised_parked_position[Z_AXIS], destination[Z_AXIS]);
  6381. delayed_move_time = millis();
  6382. return false;
  6383. }
  6384. }
  6385. delayed_move_time = 0;
  6386. // unpark extruder: 1) raise, 2) move into starting XY position, 3) lower
  6387. planner.buffer_line(raised_parked_position[X_AXIS], raised_parked_position[Y_AXIS], raised_parked_position[Z_AXIS], current_position[E_AXIS], planner.max_feedrate[Z_AXIS], active_extruder);
  6388. planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], raised_parked_position[Z_AXIS], current_position[E_AXIS], min(planner.max_feedrate[X_AXIS], planner.max_feedrate[Y_AXIS]), active_extruder);
  6389. planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], planner.max_feedrate[Z_AXIS], active_extruder);
  6390. active_extruder_parked = false;
  6391. }
  6392. }
  6393. return true;
  6394. }
  6395. #endif // DUAL_X_CARRIAGE
  6396. #if DISABLED(DELTA) && DISABLED(SCARA)
  6397. inline bool prepare_move_cartesian() {
  6398. // Do not use feedrate_multiplier for E or Z only moves
  6399. if (current_position[X_AXIS] == destination[X_AXIS] && current_position[Y_AXIS] == destination[Y_AXIS]) {
  6400. line_to_destination();
  6401. }
  6402. else {
  6403. #if ENABLED(MESH_BED_LEVELING)
  6404. mesh_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], (feedrate / 60) * (feedrate_multiplier / 100.0), active_extruder);
  6405. return false;
  6406. #else
  6407. line_to_destination(feedrate * feedrate_multiplier / 100.0);
  6408. #endif
  6409. }
  6410. return true;
  6411. }
  6412. #endif // !DELTA && !SCARA
  6413. /**
  6414. * Prepare a single move and get ready for the next one
  6415. *
  6416. * (This may call planner.buffer_line several times to put
  6417. * smaller moves into the planner for DELTA or SCARA.)
  6418. */
  6419. void prepare_move() {
  6420. clamp_to_software_endstops(destination);
  6421. refresh_cmd_timeout();
  6422. #if ENABLED(PREVENT_DANGEROUS_EXTRUDE)
  6423. prevent_dangerous_extrude(current_position[E_AXIS], destination[E_AXIS]);
  6424. #endif
  6425. #if ENABLED(SCARA)
  6426. if (!prepare_move_scara(destination)) return;
  6427. #elif ENABLED(DELTA)
  6428. if (!prepare_move_delta(destination)) return;
  6429. #else
  6430. #if ENABLED(DUAL_X_CARRIAGE)
  6431. if (!prepare_move_dual_x_carriage()) return;
  6432. #endif
  6433. if (!prepare_move_cartesian()) return;
  6434. #endif
  6435. set_current_to_destination();
  6436. }
  6437. #if ENABLED(ARC_SUPPORT)
  6438. /**
  6439. * Plan an arc in 2 dimensions
  6440. *
  6441. * The arc is approximated by generating many small linear segments.
  6442. * The length of each segment is configured in MM_PER_ARC_SEGMENT (Default 1mm)
  6443. * Arcs should only be made relatively large (over 5mm), as larger arcs with
  6444. * larger segments will tend to be more efficient. Your slicer should have
  6445. * options for G2/G3 arc generation. In future these options may be GCode tunable.
  6446. */
  6447. void plan_arc(
  6448. float target[NUM_AXIS], // Destination position
  6449. float* offset, // Center of rotation relative to current_position
  6450. uint8_t clockwise // Clockwise?
  6451. ) {
  6452. float radius = hypot(offset[X_AXIS], offset[Y_AXIS]),
  6453. center_X = current_position[X_AXIS] + offset[X_AXIS],
  6454. center_Y = current_position[Y_AXIS] + offset[Y_AXIS],
  6455. linear_travel = target[Z_AXIS] - current_position[Z_AXIS],
  6456. extruder_travel = target[E_AXIS] - current_position[E_AXIS],
  6457. r_X = -offset[X_AXIS], // Radius vector from center to current location
  6458. r_Y = -offset[Y_AXIS],
  6459. rt_X = target[X_AXIS] - center_X,
  6460. rt_Y = target[Y_AXIS] - center_Y;
  6461. // CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required.
  6462. float angular_travel = atan2(r_X * rt_Y - r_Y * rt_X, r_X * rt_X + r_Y * rt_Y);
  6463. if (angular_travel < 0) angular_travel += RADIANS(360);
  6464. if (clockwise) angular_travel -= RADIANS(360);
  6465. // Make a circle if the angular rotation is 0
  6466. if (angular_travel == 0 && current_position[X_AXIS] == target[X_AXIS] && current_position[Y_AXIS] == target[Y_AXIS])
  6467. angular_travel += RADIANS(360);
  6468. float mm_of_travel = hypot(angular_travel * radius, fabs(linear_travel));
  6469. if (mm_of_travel < 0.001) return;
  6470. uint16_t segments = floor(mm_of_travel / (MM_PER_ARC_SEGMENT));
  6471. if (segments == 0) segments = 1;
  6472. float theta_per_segment = angular_travel / segments;
  6473. float linear_per_segment = linear_travel / segments;
  6474. float extruder_per_segment = extruder_travel / segments;
  6475. /**
  6476. * Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector,
  6477. * and phi is the angle of rotation. Based on the solution approach by Jens Geisler.
  6478. * r_T = [cos(phi) -sin(phi);
  6479. * sin(phi) cos(phi] * r ;
  6480. *
  6481. * For arc generation, the center of the circle is the axis of rotation and the radius vector is
  6482. * defined from the circle center to the initial position. Each line segment is formed by successive
  6483. * vector rotations. This requires only two cos() and sin() computations to form the rotation
  6484. * matrix for the duration of the entire arc. Error may accumulate from numerical round-off, since
  6485. * all double numbers are single precision on the Arduino. (True double precision will not have
  6486. * round off issues for CNC applications.) Single precision error can accumulate to be greater than
  6487. * tool precision in some cases. Therefore, arc path correction is implemented.
  6488. *
  6489. * Small angle approximation may be used to reduce computation overhead further. This approximation
  6490. * holds for everything, but very small circles and large MM_PER_ARC_SEGMENT values. In other words,
  6491. * theta_per_segment would need to be greater than 0.1 rad and N_ARC_CORRECTION would need to be large
  6492. * to cause an appreciable drift error. N_ARC_CORRECTION~=25 is more than small enough to correct for
  6493. * numerical drift error. N_ARC_CORRECTION may be on the order a hundred(s) before error becomes an
  6494. * issue for CNC machines with the single precision Arduino calculations.
  6495. *
  6496. * This approximation also allows plan_arc to immediately insert a line segment into the planner
  6497. * without the initial overhead of computing cos() or sin(). By the time the arc needs to be applied
  6498. * a correction, the planner should have caught up to the lag caused by the initial plan_arc overhead.
  6499. * This is important when there are successive arc motions.
  6500. */
  6501. // Vector rotation matrix values
  6502. float cos_T = 1 - 0.5 * theta_per_segment * theta_per_segment; // Small angle approximation
  6503. float sin_T = theta_per_segment;
  6504. float arc_target[NUM_AXIS];
  6505. float sin_Ti, cos_Ti, r_new_Y;
  6506. uint16_t i;
  6507. int8_t count = 0;
  6508. // Initialize the linear axis
  6509. arc_target[Z_AXIS] = current_position[Z_AXIS];
  6510. // Initialize the extruder axis
  6511. arc_target[E_AXIS] = current_position[E_AXIS];
  6512. float feed_rate = feedrate * feedrate_multiplier / 60 / 100.0;
  6513. millis_t next_idle_ms = millis() + 200UL;
  6514. for (i = 1; i < segments; i++) { // Iterate (segments-1) times
  6515. thermalManager.manage_heater();
  6516. millis_t now = millis();
  6517. if (ELAPSED(now, next_idle_ms)) {
  6518. next_idle_ms = now + 200UL;
  6519. idle();
  6520. }
  6521. if (++count < N_ARC_CORRECTION) {
  6522. // Apply vector rotation matrix to previous r_X / 1
  6523. r_new_Y = r_X * sin_T + r_Y * cos_T;
  6524. r_X = r_X * cos_T - r_Y * sin_T;
  6525. r_Y = r_new_Y;
  6526. }
  6527. else {
  6528. // Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments.
  6529. // Compute exact location by applying transformation matrix from initial radius vector(=-offset).
  6530. // To reduce stuttering, the sin and cos could be computed at different times.
  6531. // For now, compute both at the same time.
  6532. cos_Ti = cos(i * theta_per_segment);
  6533. sin_Ti = sin(i * theta_per_segment);
  6534. r_X = -offset[X_AXIS] * cos_Ti + offset[Y_AXIS] * sin_Ti;
  6535. r_Y = -offset[X_AXIS] * sin_Ti - offset[Y_AXIS] * cos_Ti;
  6536. count = 0;
  6537. }
  6538. // Update arc_target location
  6539. arc_target[X_AXIS] = center_X + r_X;
  6540. arc_target[Y_AXIS] = center_Y + r_Y;
  6541. arc_target[Z_AXIS] += linear_per_segment;
  6542. arc_target[E_AXIS] += extruder_per_segment;
  6543. clamp_to_software_endstops(arc_target);
  6544. #if ENABLED(DELTA) || ENABLED(SCARA)
  6545. calculate_delta(arc_target);
  6546. #if ENABLED(AUTO_BED_LEVELING_FEATURE)
  6547. adjust_delta(arc_target);
  6548. #endif
  6549. planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], arc_target[E_AXIS], feed_rate, active_extruder);
  6550. #else
  6551. planner.buffer_line(arc_target[X_AXIS], arc_target[Y_AXIS], arc_target[Z_AXIS], arc_target[E_AXIS], feed_rate, active_extruder);
  6552. #endif
  6553. }
  6554. // Ensure last segment arrives at target location.
  6555. #if ENABLED(DELTA) || ENABLED(SCARA)
  6556. calculate_delta(target);
  6557. #if ENABLED(AUTO_BED_LEVELING_FEATURE)
  6558. adjust_delta(target);
  6559. #endif
  6560. planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], target[E_AXIS], feed_rate, active_extruder);
  6561. #else
  6562. planner.buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], feed_rate, active_extruder);
  6563. #endif
  6564. // As far as the parser is concerned, the position is now == target. In reality the
  6565. // motion control system might still be processing the action and the real tool position
  6566. // in any intermediate location.
  6567. set_current_to_destination();
  6568. }
  6569. #endif
  6570. #if ENABLED(BEZIER_CURVE_SUPPORT)
  6571. void plan_cubic_move(const float offset[4]) {
  6572. cubic_b_spline(current_position, destination, offset, feedrate * feedrate_multiplier / 60 / 100.0, active_extruder);
  6573. // As far as the parser is concerned, the position is now == target. In reality the
  6574. // motion control system might still be processing the action and the real tool position
  6575. // in any intermediate location.
  6576. set_current_to_destination();
  6577. }
  6578. #endif // BEZIER_CURVE_SUPPORT
  6579. #if HAS_CONTROLLERFAN
  6580. void controllerFan() {
  6581. static millis_t lastMotorOn = 0; // Last time a motor was turned on
  6582. static millis_t nextMotorCheck = 0; // Last time the state was checked
  6583. millis_t ms = millis();
  6584. if (ELAPSED(ms, nextMotorCheck)) {
  6585. nextMotorCheck = ms + 2500UL; // Not a time critical function, so only check every 2.5s
  6586. if (X_ENABLE_READ == X_ENABLE_ON || Y_ENABLE_READ == Y_ENABLE_ON || Z_ENABLE_READ == Z_ENABLE_ON || thermalManager.soft_pwm_bed > 0
  6587. || E0_ENABLE_READ == E_ENABLE_ON // If any of the drivers are enabled...
  6588. #if EXTRUDERS > 1
  6589. || E1_ENABLE_READ == E_ENABLE_ON
  6590. #if HAS_X2_ENABLE
  6591. || X2_ENABLE_READ == X_ENABLE_ON
  6592. #endif
  6593. #if EXTRUDERS > 2
  6594. || E2_ENABLE_READ == E_ENABLE_ON
  6595. #if EXTRUDERS > 3
  6596. || E3_ENABLE_READ == E_ENABLE_ON
  6597. #endif
  6598. #endif
  6599. #endif
  6600. ) {
  6601. lastMotorOn = ms; //... set time to NOW so the fan will turn on
  6602. }
  6603. // Fan off if no steppers have been enabled for CONTROLLERFAN_SECS seconds
  6604. uint8_t speed = (!lastMotorOn || ELAPSED(ms, lastMotorOn + (CONTROLLERFAN_SECS) * 1000UL)) ? 0 : CONTROLLERFAN_SPEED;
  6605. // allows digital or PWM fan output to be used (see M42 handling)
  6606. digitalWrite(CONTROLLERFAN_PIN, speed);
  6607. analogWrite(CONTROLLERFAN_PIN, speed);
  6608. }
  6609. }
  6610. #endif // HAS_CONTROLLERFAN
  6611. #if ENABLED(SCARA)
  6612. void calculate_SCARA_forward_Transform(float f_scara[3]) {
  6613. // Perform forward kinematics, and place results in delta[3]
  6614. // The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014
  6615. float x_sin, x_cos, y_sin, y_cos;
  6616. //SERIAL_ECHOPGM("f_delta x="); SERIAL_ECHO(f_scara[X_AXIS]);
  6617. //SERIAL_ECHOPGM(" y="); SERIAL_ECHO(f_scara[Y_AXIS]);
  6618. x_sin = sin(f_scara[X_AXIS] / SCARA_RAD2DEG) * Linkage_1;
  6619. x_cos = cos(f_scara[X_AXIS] / SCARA_RAD2DEG) * Linkage_1;
  6620. y_sin = sin(f_scara[Y_AXIS] / SCARA_RAD2DEG) * Linkage_2;
  6621. y_cos = cos(f_scara[Y_AXIS] / SCARA_RAD2DEG) * Linkage_2;
  6622. //SERIAL_ECHOPGM(" x_sin="); SERIAL_ECHO(x_sin);
  6623. //SERIAL_ECHOPGM(" x_cos="); SERIAL_ECHO(x_cos);
  6624. //SERIAL_ECHOPGM(" y_sin="); SERIAL_ECHO(y_sin);
  6625. //SERIAL_ECHOPGM(" y_cos="); SERIAL_ECHOLN(y_cos);
  6626. delta[X_AXIS] = x_cos + y_cos + SCARA_offset_x; //theta
  6627. delta[Y_AXIS] = x_sin + y_sin + SCARA_offset_y; //theta+phi
  6628. //SERIAL_ECHOPGM(" delta[X_AXIS]="); SERIAL_ECHO(delta[X_AXIS]);
  6629. //SERIAL_ECHOPGM(" delta[Y_AXIS]="); SERIAL_ECHOLN(delta[Y_AXIS]);
  6630. }
  6631. void calculate_delta(float cartesian[3]) {
  6632. //reverse kinematics.
  6633. // Perform reversed kinematics, and place results in delta[3]
  6634. // The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014
  6635. float SCARA_pos[2];
  6636. static float SCARA_C2, SCARA_S2, SCARA_K1, SCARA_K2, SCARA_theta, SCARA_psi;
  6637. SCARA_pos[X_AXIS] = cartesian[X_AXIS] * axis_scaling[X_AXIS] - SCARA_offset_x; //Translate SCARA to standard X Y
  6638. SCARA_pos[Y_AXIS] = cartesian[Y_AXIS] * axis_scaling[Y_AXIS] - SCARA_offset_y; // With scaling factor.
  6639. #if (Linkage_1 == Linkage_2)
  6640. SCARA_C2 = ((sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS])) / (2 * (float)L1_2)) - 1;
  6641. #else
  6642. SCARA_C2 = (sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS]) - (float)L1_2 - (float)L2_2) / 45000;
  6643. #endif
  6644. SCARA_S2 = sqrt(1 - sq(SCARA_C2));
  6645. SCARA_K1 = Linkage_1 + Linkage_2 * SCARA_C2;
  6646. SCARA_K2 = Linkage_2 * SCARA_S2;
  6647. SCARA_theta = (atan2(SCARA_pos[X_AXIS], SCARA_pos[Y_AXIS]) - atan2(SCARA_K1, SCARA_K2)) * -1;
  6648. SCARA_psi = atan2(SCARA_S2, SCARA_C2);
  6649. delta[X_AXIS] = SCARA_theta * SCARA_RAD2DEG; // Multiply by 180/Pi - theta is support arm angle
  6650. delta[Y_AXIS] = (SCARA_theta + SCARA_psi) * SCARA_RAD2DEG; // - equal to sub arm angle (inverted motor)
  6651. delta[Z_AXIS] = cartesian[Z_AXIS];
  6652. /**
  6653. SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]);
  6654. SERIAL_ECHOPGM(" y="); SERIAL_ECHO(cartesian[Y_AXIS]);
  6655. SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(cartesian[Z_AXIS]);
  6656. SERIAL_ECHOPGM("scara x="); SERIAL_ECHO(SCARA_pos[X_AXIS]);
  6657. SERIAL_ECHOPGM(" y="); SERIAL_ECHOLN(SCARA_pos[Y_AXIS]);
  6658. SERIAL_ECHOPGM("delta x="); SERIAL_ECHO(delta[X_AXIS]);
  6659. SERIAL_ECHOPGM(" y="); SERIAL_ECHO(delta[Y_AXIS]);
  6660. SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(delta[Z_AXIS]);
  6661. SERIAL_ECHOPGM("C2="); SERIAL_ECHO(SCARA_C2);
  6662. SERIAL_ECHOPGM(" S2="); SERIAL_ECHO(SCARA_S2);
  6663. SERIAL_ECHOPGM(" Theta="); SERIAL_ECHO(SCARA_theta);
  6664. SERIAL_ECHOPGM(" Psi="); SERIAL_ECHOLN(SCARA_psi);
  6665. SERIAL_EOL;
  6666. */
  6667. }
  6668. #endif // SCARA
  6669. #if ENABLED(TEMP_STAT_LEDS)
  6670. static bool red_led = false;
  6671. static millis_t next_status_led_update_ms = 0;
  6672. void handle_status_leds(void) {
  6673. float max_temp = 0.0;
  6674. if (ELAPSED(millis(), next_status_led_update_ms)) {
  6675. next_status_led_update_ms += 500; // Update every 0.5s
  6676. for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder)
  6677. max_temp = max(max(max_temp, thermalManager.degHotend(cur_extruder)), thermalManager.degTargetHotend(cur_extruder));
  6678. #if HAS_TEMP_BED
  6679. max_temp = max(max(max_temp, thermalManager.degTargetBed()), thermalManager.degBed());
  6680. #endif
  6681. bool new_led = (max_temp > 55.0) ? true : (max_temp < 54.0) ? false : red_led;
  6682. if (new_led != red_led) {
  6683. red_led = new_led;
  6684. digitalWrite(STAT_LED_RED, new_led ? HIGH : LOW);
  6685. digitalWrite(STAT_LED_BLUE, new_led ? LOW : HIGH);
  6686. }
  6687. }
  6688. }
  6689. #endif
  6690. void enable_all_steppers() {
  6691. enable_x();
  6692. enable_y();
  6693. enable_z();
  6694. enable_e0();
  6695. enable_e1();
  6696. enable_e2();
  6697. enable_e3();
  6698. }
  6699. void disable_all_steppers() {
  6700. disable_x();
  6701. disable_y();
  6702. disable_z();
  6703. disable_e0();
  6704. disable_e1();
  6705. disable_e2();
  6706. disable_e3();
  6707. }
  6708. /**
  6709. * Standard idle routine keeps the machine alive
  6710. */
  6711. void idle(
  6712. #if ENABLED(FILAMENTCHANGEENABLE)
  6713. bool no_stepper_sleep/*=false*/
  6714. #endif
  6715. ) {
  6716. thermalManager.manage_heater();
  6717. manage_inactivity(
  6718. #if ENABLED(FILAMENTCHANGEENABLE)
  6719. no_stepper_sleep
  6720. #endif
  6721. );
  6722. host_keepalive();
  6723. lcd_update();
  6724. #if ENABLED(PRINTCOUNTER)
  6725. print_job_timer.tick();
  6726. #endif
  6727. }
  6728. /**
  6729. * Manage several activities:
  6730. * - Check for Filament Runout
  6731. * - Keep the command buffer full
  6732. * - Check for maximum inactive time between commands
  6733. * - Check for maximum inactive time between stepper commands
  6734. * - Check if pin CHDK needs to go LOW
  6735. * - Check for KILL button held down
  6736. * - Check for HOME button held down
  6737. * - Check if cooling fan needs to be switched on
  6738. * - Check if an idle but hot extruder needs filament extruded (EXTRUDER_RUNOUT_PREVENT)
  6739. */
  6740. void manage_inactivity(bool ignore_stepper_queue/*=false*/) {
  6741. #if HAS_FILRUNOUT
  6742. if (IS_SD_PRINTING && !(READ(FILRUNOUT_PIN) ^ FIL_RUNOUT_INVERTING))
  6743. handle_filament_runout();
  6744. #endif
  6745. if (commands_in_queue < BUFSIZE) get_available_commands();
  6746. millis_t ms = millis();
  6747. if (max_inactive_time && ELAPSED(ms, previous_cmd_ms + max_inactive_time)) kill(PSTR(MSG_KILLED));
  6748. if (stepper_inactive_time && ELAPSED(ms, previous_cmd_ms + stepper_inactive_time)
  6749. && !ignore_stepper_queue && !planner.blocks_queued()) {
  6750. #if ENABLED(DISABLE_INACTIVE_X)
  6751. disable_x();
  6752. #endif
  6753. #if ENABLED(DISABLE_INACTIVE_Y)
  6754. disable_y();
  6755. #endif
  6756. #if ENABLED(DISABLE_INACTIVE_Z)
  6757. disable_z();
  6758. #endif
  6759. #if ENABLED(DISABLE_INACTIVE_E)
  6760. disable_e0();
  6761. disable_e1();
  6762. disable_e2();
  6763. disable_e3();
  6764. #endif
  6765. }
  6766. #ifdef CHDK // Check if pin should be set to LOW after M240 set it to HIGH
  6767. if (chdkActive && PENDING(ms, chdkHigh + CHDK_DELAY)) {
  6768. chdkActive = false;
  6769. WRITE(CHDK, LOW);
  6770. }
  6771. #endif
  6772. #if HAS_KILL
  6773. // Check if the kill button was pressed and wait just in case it was an accidental
  6774. // key kill key press
  6775. // -------------------------------------------------------------------------------
  6776. static int killCount = 0; // make the inactivity button a bit less responsive
  6777. const int KILL_DELAY = 750;
  6778. if (!READ(KILL_PIN))
  6779. killCount++;
  6780. else if (killCount > 0)
  6781. killCount--;
  6782. // Exceeded threshold and we can confirm that it was not accidental
  6783. // KILL the machine
  6784. // ----------------------------------------------------------------
  6785. if (killCount >= KILL_DELAY) kill(PSTR(MSG_KILLED));
  6786. #endif
  6787. #if HAS_HOME
  6788. // Check to see if we have to home, use poor man's debouncer
  6789. // ---------------------------------------------------------
  6790. static int homeDebounceCount = 0; // poor man's debouncing count
  6791. const int HOME_DEBOUNCE_DELAY = 2500;
  6792. if (!READ(HOME_PIN)) {
  6793. if (!homeDebounceCount) {
  6794. enqueue_and_echo_commands_P(PSTR("G28"));
  6795. LCD_MESSAGEPGM(MSG_AUTO_HOME);
  6796. }
  6797. if (homeDebounceCount < HOME_DEBOUNCE_DELAY)
  6798. homeDebounceCount++;
  6799. else
  6800. homeDebounceCount = 0;
  6801. }
  6802. #endif
  6803. #if HAS_CONTROLLERFAN
  6804. controllerFan(); // Check if fan should be turned on to cool stepper drivers down
  6805. #endif
  6806. #if ENABLED(EXTRUDER_RUNOUT_PREVENT)
  6807. if (ELAPSED(ms, previous_cmd_ms + (EXTRUDER_RUNOUT_SECONDS) * 1000UL))
  6808. if (thermalManager.degHotend(active_extruder) > EXTRUDER_RUNOUT_MINTEMP) {
  6809. bool oldstatus;
  6810. switch (active_extruder) {
  6811. case 0:
  6812. oldstatus = E0_ENABLE_READ;
  6813. enable_e0();
  6814. break;
  6815. #if EXTRUDERS > 1
  6816. case 1:
  6817. oldstatus = E1_ENABLE_READ;
  6818. enable_e1();
  6819. break;
  6820. #if EXTRUDERS > 2
  6821. case 2:
  6822. oldstatus = E2_ENABLE_READ;
  6823. enable_e2();
  6824. break;
  6825. #if EXTRUDERS > 3
  6826. case 3:
  6827. oldstatus = E3_ENABLE_READ;
  6828. enable_e3();
  6829. break;
  6830. #endif
  6831. #endif
  6832. #endif
  6833. }
  6834. float oldepos = current_position[E_AXIS], oldedes = destination[E_AXIS];
  6835. planner.buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS],
  6836. destination[E_AXIS] + (EXTRUDER_RUNOUT_EXTRUDE) * (EXTRUDER_RUNOUT_ESTEPS) / planner.axis_steps_per_unit[E_AXIS],
  6837. (EXTRUDER_RUNOUT_SPEED) / 60. * (EXTRUDER_RUNOUT_ESTEPS) / planner.axis_steps_per_unit[E_AXIS], active_extruder);
  6838. current_position[E_AXIS] = oldepos;
  6839. destination[E_AXIS] = oldedes;
  6840. planner.set_e_position_mm(oldepos);
  6841. previous_cmd_ms = ms; // refresh_cmd_timeout()
  6842. stepper.synchronize();
  6843. switch (active_extruder) {
  6844. case 0:
  6845. E0_ENABLE_WRITE(oldstatus);
  6846. break;
  6847. #if EXTRUDERS > 1
  6848. case 1:
  6849. E1_ENABLE_WRITE(oldstatus);
  6850. break;
  6851. #if EXTRUDERS > 2
  6852. case 2:
  6853. E2_ENABLE_WRITE(oldstatus);
  6854. break;
  6855. #if EXTRUDERS > 3
  6856. case 3:
  6857. E3_ENABLE_WRITE(oldstatus);
  6858. break;
  6859. #endif
  6860. #endif
  6861. #endif
  6862. }
  6863. }
  6864. #endif
  6865. #if ENABLED(DUAL_X_CARRIAGE)
  6866. // handle delayed move timeout
  6867. if (delayed_move_time && ELAPSED(ms, delayed_move_time + 1000UL) && IsRunning()) {
  6868. // travel moves have been received so enact them
  6869. delayed_move_time = 0xFFFFFFFFUL; // force moves to be done
  6870. set_destination_to_current();
  6871. prepare_move();
  6872. }
  6873. #endif
  6874. #if ENABLED(TEMP_STAT_LEDS)
  6875. handle_status_leds();
  6876. #endif
  6877. planner.check_axes_activity();
  6878. }
  6879. void kill(const char* lcd_msg) {
  6880. #if ENABLED(ULTRA_LCD)
  6881. lcd_setalertstatuspgm(lcd_msg);
  6882. #else
  6883. UNUSED(lcd_msg);
  6884. #endif
  6885. cli(); // Stop interrupts
  6886. thermalManager.disable_all_heaters();
  6887. disable_all_steppers();
  6888. #if HAS_POWER_SWITCH
  6889. pinMode(PS_ON_PIN, INPUT);
  6890. #endif
  6891. SERIAL_ERROR_START;
  6892. SERIAL_ERRORLNPGM(MSG_ERR_KILLED);
  6893. // FMC small patch to update the LCD before ending
  6894. sei(); // enable interrupts
  6895. for (int i = 5; i--; lcd_update()) delay(200); // Wait a short time
  6896. cli(); // disable interrupts
  6897. suicide();
  6898. while (1) {
  6899. #if ENABLED(USE_WATCHDOG)
  6900. watchdog_reset();
  6901. #endif
  6902. } // Wait for reset
  6903. }
  6904. #if ENABLED(FILAMENT_RUNOUT_SENSOR)
  6905. void handle_filament_runout() {
  6906. if (!filament_ran_out) {
  6907. filament_ran_out = true;
  6908. enqueue_and_echo_commands_P(PSTR(FILAMENT_RUNOUT_SCRIPT));
  6909. stepper.synchronize();
  6910. }
  6911. }
  6912. #endif // FILAMENT_RUNOUT_SENSOR
  6913. #if ENABLED(FAST_PWM_FAN)
  6914. void setPwmFrequency(uint8_t pin, int val) {
  6915. val &= 0x07;
  6916. switch (digitalPinToTimer(pin)) {
  6917. #if defined(TCCR0A)
  6918. case TIMER0A:
  6919. case TIMER0B:
  6920. // TCCR0B &= ~(_BV(CS00) | _BV(CS01) | _BV(CS02));
  6921. // TCCR0B |= val;
  6922. break;
  6923. #endif
  6924. #if defined(TCCR1A)
  6925. case TIMER1A:
  6926. case TIMER1B:
  6927. // TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
  6928. // TCCR1B |= val;
  6929. break;
  6930. #endif
  6931. #if defined(TCCR2)
  6932. case TIMER2:
  6933. case TIMER2:
  6934. TCCR2 &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
  6935. TCCR2 |= val;
  6936. break;
  6937. #endif
  6938. #if defined(TCCR2A)
  6939. case TIMER2A:
  6940. case TIMER2B:
  6941. TCCR2B &= ~(_BV(CS20) | _BV(CS21) | _BV(CS22));
  6942. TCCR2B |= val;
  6943. break;
  6944. #endif
  6945. #if defined(TCCR3A)
  6946. case TIMER3A:
  6947. case TIMER3B:
  6948. case TIMER3C:
  6949. TCCR3B &= ~(_BV(CS30) | _BV(CS31) | _BV(CS32));
  6950. TCCR3B |= val;
  6951. break;
  6952. #endif
  6953. #if defined(TCCR4A)
  6954. case TIMER4A:
  6955. case TIMER4B:
  6956. case TIMER4C:
  6957. TCCR4B &= ~(_BV(CS40) | _BV(CS41) | _BV(CS42));
  6958. TCCR4B |= val;
  6959. break;
  6960. #endif
  6961. #if defined(TCCR5A)
  6962. case TIMER5A:
  6963. case TIMER5B:
  6964. case TIMER5C:
  6965. TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52));
  6966. TCCR5B |= val;
  6967. break;
  6968. #endif
  6969. }
  6970. }
  6971. #endif // FAST_PWM_FAN
  6972. void stop() {
  6973. thermalManager.disable_all_heaters();
  6974. if (IsRunning()) {
  6975. Running = false;
  6976. Stopped_gcode_LastN = gcode_LastN; // Save last g_code for restart
  6977. SERIAL_ERROR_START;
  6978. SERIAL_ERRORLNPGM(MSG_ERR_STOPPED);
  6979. LCD_MESSAGEPGM(MSG_STOPPED);
  6980. }
  6981. }
  6982. float calculate_volumetric_multiplier(float diameter) {
  6983. if (!volumetric_enabled || diameter == 0) return 1.0;
  6984. float d2 = diameter * 0.5;
  6985. return 1.0 / (M_PI * d2 * d2);
  6986. }
  6987. void calculate_volumetric_multipliers() {
  6988. for (int i = 0; i < EXTRUDERS; i++)
  6989. volumetric_multiplier[i] = calculate_volumetric_multiplier(filament_size[i]);
  6990. }