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

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