Marlin_main.cpp 289 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812181318141815181618171818181918201821182218231824182518261827182818291830183118321833183418351836183718381839184018411842184318441845184618471848184918501851185218531854185518561857185818591860186118621863186418651866186718681869187018711872187318741875187618771878187918801881188218831884188518861887188818891890189118921893189418951896189718981899190019011902190319041905190619071908190919101911191219131914191519161917191819191920192119221923192419251926192719281929193019311932193319341935193619371938193919401941194219431944194519461947194819491950195119521953195419551956195719581959196019611962196319641965196619671968196919701971197219731974197519761977197819791980198119821983198419851986198719881989199019911992199319941995199619971998199920002001200220032004200520062007200820092010201120122013201420152016201720182019202020212022202320242025202620272028202920302031203220332034203520362037203820392040204120422043204420452046204720482049205020512052205320542055205620572058205920602061206220632064206520662067206820692070207120722073207420752076207720782079208020812082208320842085208620872088208920902091209220932094209520962097209820992100210121022103210421052106210721082109211021112112211321142115211621172118211921202121212221232124212521262127212821292130213121322133213421352136213721382139214021412142214321442145214621472148214921502151215221532154215521562157215821592160216121622163216421652166216721682169217021712172217321742175217621772178217921802181218221832184218521862187218821892190219121922193219421952196219721982199220022012202220322042205220622072208220922102211221222132214221522162217221822192220222122222223222422252226222722282229223022312232223322342235223622372238223922402241224222432244224522462247224822492250225122522253225422552256225722582259226022612262226322642265226622672268226922702271227222732274227522762277227822792280228122822283228422852286228722882289229022912292229322942295229622972298229923002301230223032304230523062307230823092310231123122313231423152316231723182319232023212322232323242325232623272328232923302331233223332334233523362337233823392340234123422343234423452346234723482349235023512352235323542355235623572358235923602361236223632364236523662367236823692370237123722373237423752376237723782379238023812382238323842385238623872388238923902391239223932394239523962397239823992400240124022403240424052406240724082409241024112412241324142415241624172418241924202421242224232424242524262427242824292430243124322433243424352436243724382439244024412442244324442445244624472448244924502451245224532454245524562457245824592460246124622463246424652466246724682469247024712472247324742475247624772478247924802481248224832484248524862487248824892490249124922493249424952496249724982499250025012502250325042505250625072508250925102511251225132514251525162517251825192520252125222523252425252526252725282529253025312532253325342535253625372538253925402541254225432544254525462547254825492550255125522553255425552556255725582559256025612562256325642565256625672568256925702571257225732574257525762577257825792580258125822583258425852586258725882589259025912592259325942595259625972598259926002601260226032604260526062607260826092610261126122613261426152616261726182619262026212622262326242625262626272628262926302631263226332634263526362637263826392640264126422643264426452646264726482649265026512652265326542655265626572658265926602661266226632664266526662667266826692670267126722673267426752676267726782679268026812682268326842685268626872688268926902691269226932694269526962697269826992700270127022703270427052706270727082709271027112712271327142715271627172718271927202721272227232724272527262727272827292730273127322733273427352736273727382739274027412742274327442745274627472748274927502751275227532754275527562757275827592760276127622763276427652766276727682769277027712772277327742775277627772778277927802781278227832784278527862787278827892790279127922793279427952796279727982799280028012802280328042805280628072808280928102811281228132814281528162817281828192820282128222823282428252826282728282829283028312832283328342835283628372838283928402841284228432844284528462847284828492850285128522853285428552856285728582859286028612862286328642865286628672868286928702871287228732874287528762877287828792880288128822883288428852886288728882889289028912892289328942895289628972898289929002901290229032904290529062907290829092910291129122913291429152916291729182919292029212922292329242925292629272928292929302931293229332934293529362937293829392940294129422943294429452946294729482949295029512952295329542955295629572958295929602961296229632964296529662967296829692970297129722973297429752976297729782979298029812982298329842985298629872988298929902991299229932994299529962997299829993000300130023003300430053006300730083009301030113012301330143015301630173018301930203021302230233024302530263027302830293030303130323033303430353036303730383039304030413042304330443045304630473048304930503051305230533054305530563057305830593060306130623063306430653066306730683069307030713072307330743075307630773078307930803081308230833084308530863087308830893090309130923093309430953096309730983099310031013102310331043105310631073108310931103111311231133114311531163117311831193120312131223123312431253126312731283129313031313132313331343135313631373138313931403141314231433144314531463147314831493150315131523153315431553156315731583159316031613162316331643165316631673168316931703171317231733174317531763177317831793180318131823183318431853186318731883189319031913192319331943195319631973198319932003201320232033204320532063207320832093210321132123213321432153216321732183219322032213222322332243225322632273228322932303231323232333234323532363237323832393240324132423243324432453246324732483249325032513252325332543255325632573258325932603261326232633264326532663267326832693270327132723273327432753276327732783279328032813282328332843285328632873288328932903291329232933294329532963297329832993300330133023303330433053306330733083309331033113312331333143315331633173318331933203321332233233324332533263327332833293330333133323333333433353336333733383339334033413342334333443345334633473348334933503351335233533354335533563357335833593360336133623363336433653366336733683369337033713372337333743375337633773378337933803381338233833384338533863387338833893390339133923393339433953396339733983399340034013402340334043405340634073408340934103411341234133414341534163417341834193420342134223423342434253426342734283429343034313432343334343435343634373438343934403441344234433444344534463447344834493450345134523453345434553456345734583459346034613462346334643465346634673468346934703471347234733474347534763477347834793480348134823483348434853486348734883489349034913492349334943495349634973498349935003501350235033504350535063507350835093510351135123513351435153516351735183519352035213522352335243525352635273528352935303531353235333534353535363537353835393540354135423543354435453546354735483549355035513552355335543555355635573558355935603561356235633564356535663567356835693570357135723573357435753576357735783579358035813582358335843585358635873588358935903591359235933594359535963597359835993600360136023603360436053606360736083609361036113612361336143615361636173618361936203621362236233624362536263627362836293630363136323633363436353636363736383639364036413642364336443645364636473648364936503651365236533654365536563657365836593660366136623663366436653666366736683669367036713672367336743675367636773678367936803681368236833684368536863687368836893690369136923693369436953696369736983699370037013702370337043705370637073708370937103711371237133714371537163717371837193720372137223723372437253726372737283729373037313732373337343735373637373738373937403741374237433744374537463747374837493750375137523753375437553756375737583759376037613762376337643765376637673768376937703771377237733774377537763777377837793780378137823783378437853786378737883789379037913792379337943795379637973798379938003801380238033804380538063807380838093810381138123813381438153816381738183819382038213822382338243825382638273828382938303831383238333834383538363837383838393840384138423843384438453846384738483849385038513852385338543855385638573858385938603861386238633864386538663867386838693870387138723873387438753876387738783879388038813882388338843885388638873888388938903891389238933894389538963897389838993900390139023903390439053906390739083909391039113912391339143915391639173918391939203921392239233924392539263927392839293930393139323933393439353936393739383939394039413942394339443945394639473948394939503951395239533954395539563957395839593960396139623963396439653966396739683969397039713972397339743975397639773978397939803981398239833984398539863987398839893990399139923993399439953996399739983999400040014002400340044005400640074008400940104011401240134014401540164017401840194020402140224023402440254026402740284029403040314032403340344035403640374038403940404041404240434044404540464047404840494050405140524053405440554056405740584059406040614062406340644065406640674068406940704071407240734074407540764077407840794080408140824083408440854086408740884089409040914092409340944095409640974098409941004101410241034104410541064107410841094110411141124113411441154116411741184119412041214122412341244125412641274128412941304131413241334134413541364137413841394140414141424143414441454146414741484149415041514152415341544155415641574158415941604161416241634164416541664167416841694170417141724173417441754176417741784179418041814182418341844185418641874188418941904191419241934194419541964197419841994200420142024203420442054206420742084209421042114212421342144215421642174218421942204221422242234224422542264227422842294230423142324233423442354236423742384239424042414242424342444245424642474248424942504251425242534254425542564257425842594260426142624263426442654266426742684269427042714272427342744275427642774278427942804281428242834284428542864287428842894290429142924293429442954296429742984299430043014302430343044305430643074308430943104311431243134314431543164317431843194320432143224323432443254326432743284329433043314332433343344335433643374338433943404341434243434344434543464347434843494350435143524353435443554356435743584359436043614362436343644365436643674368436943704371437243734374437543764377437843794380438143824383438443854386438743884389439043914392439343944395439643974398439944004401440244034404440544064407440844094410441144124413441444154416441744184419442044214422442344244425442644274428442944304431443244334434443544364437443844394440444144424443444444454446444744484449445044514452445344544455445644574458445944604461446244634464446544664467446844694470447144724473447444754476447744784479448044814482448344844485448644874488448944904491449244934494449544964497449844994500450145024503450445054506450745084509451045114512451345144515451645174518451945204521452245234524452545264527452845294530453145324533453445354536453745384539454045414542454345444545454645474548454945504551455245534554455545564557455845594560456145624563456445654566456745684569457045714572457345744575457645774578457945804581458245834584458545864587458845894590459145924593459445954596459745984599460046014602460346044605460646074608460946104611461246134614461546164617461846194620462146224623462446254626462746284629463046314632463346344635463646374638463946404641464246434644464546464647464846494650465146524653465446554656465746584659466046614662466346644665466646674668466946704671467246734674467546764677467846794680468146824683468446854686468746884689469046914692469346944695469646974698469947004701470247034704470547064707470847094710471147124713471447154716471747184719472047214722472347244725472647274728472947304731473247334734473547364737473847394740474147424743474447454746474747484749475047514752475347544755475647574758475947604761476247634764476547664767476847694770477147724773477447754776477747784779478047814782478347844785478647874788478947904791479247934794479547964797479847994800480148024803480448054806480748084809481048114812481348144815481648174818481948204821482248234824482548264827482848294830483148324833483448354836483748384839484048414842484348444845484648474848484948504851485248534854485548564857485848594860486148624863486448654866486748684869487048714872487348744875487648774878487948804881488248834884488548864887488848894890489148924893489448954896489748984899490049014902490349044905490649074908490949104911491249134914491549164917491849194920492149224923492449254926492749284929493049314932493349344935493649374938493949404941494249434944494549464947494849494950495149524953495449554956495749584959496049614962496349644965496649674968496949704971497249734974497549764977497849794980498149824983498449854986498749884989499049914992499349944995499649974998499950005001500250035004500550065007500850095010501150125013501450155016501750185019502050215022502350245025502650275028502950305031503250335034503550365037503850395040504150425043504450455046504750485049505050515052505350545055505650575058505950605061506250635064506550665067506850695070507150725073507450755076507750785079508050815082508350845085508650875088508950905091509250935094509550965097509850995100510151025103510451055106510751085109511051115112511351145115511651175118511951205121512251235124512551265127512851295130513151325133513451355136513751385139514051415142514351445145514651475148514951505151515251535154515551565157515851595160516151625163516451655166516751685169517051715172517351745175517651775178517951805181518251835184518551865187518851895190519151925193519451955196519751985199520052015202520352045205520652075208520952105211521252135214521552165217521852195220522152225223522452255226522752285229523052315232523352345235523652375238523952405241524252435244524552465247524852495250525152525253525452555256525752585259526052615262526352645265526652675268526952705271527252735274527552765277527852795280528152825283528452855286528752885289529052915292529352945295529652975298529953005301530253035304530553065307530853095310531153125313531453155316531753185319532053215322532353245325532653275328532953305331533253335334533553365337533853395340534153425343534453455346534753485349535053515352535353545355535653575358535953605361536253635364536553665367536853695370537153725373537453755376537753785379538053815382538353845385538653875388538953905391539253935394539553965397539853995400540154025403540454055406540754085409541054115412541354145415541654175418541954205421542254235424542554265427542854295430543154325433543454355436543754385439544054415442544354445445544654475448544954505451545254535454545554565457545854595460546154625463546454655466546754685469547054715472547354745475547654775478547954805481548254835484548554865487548854895490549154925493549454955496549754985499550055015502550355045505550655075508550955105511551255135514551555165517551855195520552155225523552455255526552755285529553055315532553355345535553655375538553955405541554255435544554555465547554855495550555155525553555455555556555755585559556055615562556355645565556655675568556955705571557255735574557555765577557855795580558155825583558455855586558755885589559055915592559355945595559655975598559956005601560256035604560556065607560856095610561156125613561456155616561756185619562056215622562356245625562656275628562956305631563256335634563556365637563856395640564156425643564456455646564756485649565056515652565356545655565656575658565956605661566256635664566556665667566856695670567156725673567456755676567756785679568056815682568356845685568656875688568956905691569256935694569556965697569856995700570157025703570457055706570757085709571057115712571357145715571657175718571957205721572257235724572557265727572857295730573157325733573457355736573757385739574057415742574357445745574657475748574957505751575257535754575557565757575857595760576157625763576457655766576757685769577057715772577357745775577657775778577957805781578257835784578557865787578857895790579157925793579457955796579757985799580058015802580358045805580658075808580958105811581258135814581558165817581858195820582158225823582458255826582758285829583058315832583358345835583658375838583958405841584258435844584558465847584858495850585158525853585458555856585758585859586058615862586358645865586658675868586958705871587258735874587558765877587858795880588158825883588458855886588758885889589058915892589358945895589658975898589959005901590259035904590559065907590859095910591159125913591459155916591759185919592059215922592359245925592659275928592959305931593259335934593559365937593859395940594159425943594459455946594759485949595059515952595359545955595659575958595959605961596259635964596559665967596859695970597159725973597459755976597759785979598059815982598359845985598659875988598959905991599259935994599559965997599859996000600160026003600460056006600760086009601060116012601360146015601660176018601960206021602260236024602560266027602860296030603160326033603460356036603760386039604060416042604360446045604660476048604960506051605260536054605560566057605860596060606160626063606460656066606760686069607060716072607360746075607660776078607960806081608260836084608560866087608860896090609160926093609460956096609760986099610061016102610361046105610661076108610961106111611261136114611561166117611861196120612161226123612461256126612761286129613061316132613361346135613661376138613961406141614261436144614561466147614861496150615161526153615461556156615761586159616061616162616361646165616661676168616961706171617261736174617561766177617861796180618161826183618461856186618761886189619061916192619361946195619661976198619962006201620262036204620562066207620862096210621162126213621462156216621762186219622062216222622362246225622662276228622962306231623262336234623562366237623862396240624162426243624462456246624762486249625062516252625362546255625662576258625962606261626262636264626562666267626862696270627162726273627462756276627762786279628062816282628362846285628662876288628962906291629262936294629562966297629862996300630163026303630463056306630763086309631063116312631363146315631663176318631963206321632263236324632563266327632863296330633163326333633463356336633763386339634063416342634363446345634663476348634963506351635263536354635563566357635863596360636163626363636463656366636763686369637063716372637363746375637663776378637963806381638263836384638563866387638863896390639163926393639463956396639763986399640064016402640364046405640664076408640964106411641264136414641564166417641864196420642164226423642464256426642764286429643064316432643364346435643664376438643964406441644264436444644564466447644864496450645164526453645464556456645764586459646064616462646364646465646664676468646964706471647264736474647564766477647864796480648164826483648464856486648764886489649064916492649364946495649664976498649965006501650265036504650565066507650865096510651165126513651465156516651765186519652065216522652365246525652665276528652965306531653265336534653565366537653865396540654165426543654465456546654765486549655065516552655365546555655665576558655965606561656265636564656565666567656865696570657165726573657465756576657765786579658065816582658365846585658665876588658965906591659265936594659565966597659865996600660166026603660466056606660766086609661066116612661366146615661666176618661966206621662266236624662566266627662866296630663166326633663466356636663766386639664066416642664366446645664666476648664966506651665266536654665566566657665866596660666166626663666466656666666766686669667066716672667366746675667666776678667966806681668266836684668566866687668866896690669166926693669466956696669766986699670067016702670367046705670667076708670967106711671267136714671567166717671867196720672167226723672467256726672767286729673067316732673367346735673667376738673967406741674267436744674567466747674867496750675167526753675467556756675767586759676067616762676367646765676667676768676967706771677267736774677567766777677867796780678167826783678467856786678767886789679067916792679367946795679667976798679968006801680268036804680568066807680868096810681168126813681468156816681768186819682068216822682368246825682668276828682968306831683268336834683568366837683868396840684168426843684468456846684768486849685068516852685368546855685668576858685968606861686268636864686568666867686868696870687168726873687468756876687768786879688068816882688368846885688668876888688968906891689268936894689568966897689868996900690169026903690469056906690769086909691069116912691369146915691669176918691969206921692269236924692569266927692869296930693169326933693469356936693769386939694069416942694369446945694669476948694969506951695269536954695569566957695869596960696169626963696469656966696769686969697069716972697369746975697669776978697969806981698269836984698569866987698869896990699169926993699469956996699769986999700070017002700370047005700670077008700970107011701270137014701570167017701870197020702170227023702470257026702770287029703070317032703370347035703670377038703970407041704270437044704570467047704870497050705170527053705470557056705770587059706070617062706370647065706670677068706970707071707270737074707570767077707870797080708170827083708470857086708770887089709070917092709370947095709670977098709971007101710271037104710571067107710871097110711171127113711471157116711771187119712071217122712371247125712671277128712971307131713271337134713571367137713871397140714171427143714471457146714771487149715071517152715371547155715671577158715971607161716271637164716571667167716871697170717171727173717471757176717771787179718071817182718371847185718671877188718971907191719271937194719571967197719871997200720172027203720472057206720772087209721072117212721372147215721672177218721972207221722272237224722572267227722872297230723172327233723472357236723772387239724072417242724372447245724672477248724972507251725272537254725572567257725872597260726172627263726472657266726772687269727072717272727372747275727672777278727972807281728272837284728572867287728872897290729172927293729472957296729772987299730073017302730373047305730673077308730973107311731273137314731573167317731873197320732173227323732473257326732773287329733073317332733373347335733673377338733973407341734273437344734573467347734873497350735173527353735473557356735773587359736073617362736373647365736673677368736973707371737273737374737573767377737873797380738173827383738473857386738773887389739073917392739373947395739673977398739974007401740274037404740574067407740874097410741174127413741474157416741774187419742074217422742374247425742674277428742974307431743274337434743574367437743874397440744174427443744474457446744774487449745074517452745374547455745674577458745974607461746274637464746574667467746874697470747174727473747474757476747774787479748074817482748374847485748674877488748974907491749274937494749574967497749874997500750175027503750475057506750775087509751075117512751375147515751675177518751975207521752275237524752575267527752875297530753175327533753475357536753775387539754075417542754375447545754675477548754975507551755275537554755575567557755875597560756175627563756475657566756775687569757075717572757375747575757675777578757975807581758275837584758575867587758875897590759175927593759475957596759775987599760076017602760376047605760676077608760976107611761276137614761576167617761876197620762176227623762476257626762776287629763076317632763376347635763676377638763976407641764276437644764576467647764876497650765176527653765476557656765776587659766076617662766376647665766676677668766976707671767276737674767576767677767876797680768176827683768476857686768776887689769076917692769376947695769676977698769977007701770277037704770577067707770877097710771177127713771477157716771777187719772077217722772377247725772677277728772977307731773277337734773577367737773877397740774177427743774477457746774777487749775077517752775377547755775677577758775977607761776277637764776577667767776877697770777177727773777477757776777777787779778077817782778377847785778677877788778977907791779277937794779577967797779877997800780178027803780478057806780778087809781078117812781378147815781678177818781978207821782278237824782578267827782878297830783178327833783478357836783778387839784078417842784378447845784678477848784978507851785278537854785578567857785878597860786178627863786478657866786778687869787078717872787378747875787678777878787978807881788278837884788578867887788878897890789178927893789478957896789778987899790079017902790379047905790679077908790979107911791279137914791579167917791879197920792179227923792479257926792779287929793079317932793379347935793679377938793979407941794279437944794579467947794879497950795179527953795479557956795779587959796079617962796379647965796679677968796979707971797279737974797579767977797879797980798179827983798479857986798779887989799079917992799379947995799679977998799980008001800280038004800580068007800880098010801180128013801480158016801780188019802080218022802380248025802680278028802980308031803280338034803580368037803880398040804180428043804480458046804780488049805080518052805380548055805680578058805980608061806280638064806580668067806880698070807180728073807480758076807780788079808080818082808380848085808680878088808980908091809280938094809580968097809880998100810181028103810481058106810781088109811081118112811381148115811681178118811981208121812281238124812581268127812881298130813181328133813481358136813781388139814081418142814381448145814681478148814981508151815281538154815581568157815881598160816181628163816481658166816781688169817081718172817381748175817681778178817981808181818281838184818581868187818881898190819181928193819481958196819781988199820082018202820382048205820682078208820982108211821282138214821582168217821882198220822182228223822482258226822782288229823082318232823382348235823682378238823982408241824282438244824582468247824882498250825182528253825482558256825782588259826082618262826382648265826682678268826982708271827282738274827582768277827882798280828182828283828482858286828782888289829082918292829382948295829682978298829983008301830283038304830583068307830883098310831183128313831483158316831783188319832083218322832383248325832683278328832983308331833283338334833583368337833883398340834183428343834483458346834783488349835083518352835383548355835683578358835983608361836283638364836583668367836883698370837183728373837483758376837783788379838083818382838383848385838683878388838983908391839283938394839583968397839883998400840184028403840484058406840784088409841084118412841384148415841684178418841984208421842284238424842584268427842884298430843184328433843484358436843784388439844084418442844384448445844684478448844984508451845284538454845584568457845884598460846184628463846484658466846784688469847084718472847384748475847684778478847984808481848284838484848584868487848884898490849184928493849484958496849784988499850085018502850385048505850685078508850985108511851285138514851585168517851885198520852185228523852485258526852785288529853085318532853385348535853685378538853985408541854285438544854585468547854885498550855185528553855485558556855785588559856085618562856385648565856685678568856985708571857285738574857585768577857885798580858185828583858485858586858785888589859085918592859385948595859685978598859986008601860286038604860586068607860886098610861186128613861486158616861786188619862086218622862386248625862686278628862986308631863286338634863586368637
  1. /* -*- c++ -*- */
  2. /*
  3. Reprap firmware based on Sprinter and grbl.
  4. Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
  5. This program is free software: you can redistribute it and/or modify
  6. it under the terms of the GNU General Public License as published by
  7. the Free Software Foundation, either version 3 of the License, or
  8. (at your option) any later version.
  9. This program is distributed in the hope that it will be useful,
  10. but WITHOUT ANY WARRANTY; without even the implied warranty of
  11. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  12. GNU General Public License for more details.
  13. You should have received a copy of the GNU General Public License
  14. along with this program. If not, see <http://www.gnu.org/licenses/>.
  15. */
  16. /*
  17. This firmware is a mashup between Sprinter and grbl.
  18. (https://github.com/kliment/Sprinter)
  19. (https://github.com/simen/grbl/tree)
  20. It has preliminary support for Matthew Roberts advance algorithm
  21. http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
  22. */
  23. #include "Marlin.h"
  24. #ifdef ENABLE_AUTO_BED_LEVELING
  25. #include "vector_3.h"
  26. #ifdef AUTO_BED_LEVELING_GRID
  27. #include "qr_solve.h"
  28. #endif
  29. #endif // ENABLE_AUTO_BED_LEVELING
  30. #ifdef MESH_BED_LEVELING
  31. #include "mesh_bed_leveling.h"
  32. #include "mesh_bed_calibration.h"
  33. #endif
  34. #include "printers.h"
  35. #include "ultralcd.h"
  36. #include "Configuration_prusa.h"
  37. #include "planner.h"
  38. #include "stepper.h"
  39. #include "temperature.h"
  40. #include "motion_control.h"
  41. #include "cardreader.h"
  42. #include "ConfigurationStore.h"
  43. #include "language.h"
  44. #include "pins_arduino.h"
  45. #include "math.h"
  46. #include "util.h"
  47. #include "Timer.h"
  48. #include <avr/wdt.h>
  49. #include <avr/pgmspace.h>
  50. #include "Dcodes.h"
  51. #ifdef SWSPI
  52. #include "swspi.h"
  53. #endif //SWSPI
  54. #ifdef NEW_SPI
  55. #include "spi.h"
  56. #endif //NEW_SPI
  57. #ifdef SWI2C
  58. #include "swi2c.h"
  59. #endif //SWI2C
  60. #ifdef PAT9125
  61. #include "pat9125.h"
  62. #include "fsensor.h"
  63. #endif //PAT9125
  64. #ifdef TMC2130
  65. #include "tmc2130.h"
  66. #endif //TMC2130
  67. #ifdef BLINKM
  68. #include "BlinkM.h"
  69. #include "Wire.h"
  70. #endif
  71. #ifdef ULTRALCD
  72. #include "ultralcd.h"
  73. #endif
  74. #if NUM_SERVOS > 0
  75. #include "Servo.h"
  76. #endif
  77. #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
  78. #include <SPI.h>
  79. #endif
  80. #define VERSION_STRING "1.0.2"
  81. #include "ultralcd.h"
  82. #include "cmdqueue.h"
  83. // Macros for bit masks
  84. #define BIT(b) (1<<(b))
  85. #define TEST(n,b) (((n)&BIT(b))!=0)
  86. #define SET_BIT(n,b,value) (n) ^= ((-value)^(n)) & (BIT(b))
  87. //Macro for print fan speed
  88. #define FAN_PULSE_WIDTH_LIMIT ((fanSpeed > 100) ? 3 : 4) //time in ms
  89. // look here for descriptions of G-codes: http://linuxcnc.org/handbook/gcode/g-code.html
  90. // http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
  91. //Implemented Codes
  92. //-------------------
  93. // PRUSA CODES
  94. // P F - Returns FW versions
  95. // P R - Returns revision of printer
  96. // G0 -> G1
  97. // G1 - Coordinated Movement X Y Z E
  98. // G2 - CW ARC
  99. // G3 - CCW ARC
  100. // G4 - Dwell S<seconds> or P<milliseconds>
  101. // G10 - retract filament according to settings of M207
  102. // G11 - retract recover filament according to settings of M208
  103. // G28 - Home all Axis
  104. // G29 - Detailed Z-Probe, probes the bed at 3 or more points. Will fail if you haven't homed yet.
  105. // G30 - Single Z Probe, probes bed at current XY location.
  106. // G31 - Dock sled (Z_PROBE_SLED only)
  107. // G32 - Undock sled (Z_PROBE_SLED only)
  108. // G80 - Automatic mesh bed leveling
  109. // G81 - Print bed profile
  110. // G90 - Use Absolute Coordinates
  111. // G91 - Use Relative Coordinates
  112. // G92 - Set current position to coordinates given
  113. // M Codes
  114. // M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled)
  115. // M1 - Same as M0
  116. // M17 - Enable/Power all stepper motors
  117. // M18 - Disable all stepper motors; same as M84
  118. // M20 - List SD card
  119. // M21 - Init SD card
  120. // M22 - Release SD card
  121. // M23 - Select SD file (M23 filename.g)
  122. // M24 - Start/resume SD print
  123. // M25 - Pause SD print
  124. // M26 - Set SD position in bytes (M26 S12345)
  125. // M27 - Report SD print status
  126. // M28 - Start SD write (M28 filename.g)
  127. // M29 - Stop SD write
  128. // M30 - Delete file from SD (M30 filename.g)
  129. // M31 - Output time since last M109 or SD card start to serial
  130. // M32 - Select file and start SD print (Can be used _while_ printing from SD card files):
  131. // syntax "M32 /path/filename#", or "M32 S<startpos bytes> !filename#"
  132. // Call gcode file : "M32 P !filename#" and return to caller file after finishing (similar to #include).
  133. // The '#' is necessary when calling from within sd files, as it stops buffer prereading
  134. // 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.
  135. // M80 - Turn on Power Supply
  136. // M81 - Turn off Power Supply
  137. // M82 - Set E codes absolute (default)
  138. // M83 - Set E codes relative while in Absolute Coordinates (G90) mode
  139. // M84 - Disable steppers until next move,
  140. // or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
  141. // M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
  142. // M92 - Set axis_steps_per_unit - same syntax as G92
  143. // M104 - Set extruder target temp
  144. // M105 - Read current temp
  145. // M106 - Fan on
  146. // M107 - Fan off
  147. // M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating
  148. // Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling
  149. // IF AUTOTEMP is enabled, S<mintemp> B<maxtemp> F<factor>. Exit autotemp by any M109 without F
  150. // M112 - Emergency stop
  151. // M113 - Get or set the timeout interval for Host Keepalive "busy" messages
  152. // M114 - Output current position to serial port
  153. // M115 - Capabilities string
  154. // M117 - display message
  155. // M119 - Output Endstop status to serial port
  156. // M126 - Solenoid Air Valve Open (BariCUDA support by jmil)
  157. // M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil)
  158. // M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil)
  159. // M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil)
  160. // M140 - Set bed target temp
  161. // 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.
  162. // M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating
  163. // Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
  164. // M200 D<millimeters>- set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).
  165. // M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
  166. // M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
  167. // M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
  168. // M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) in mm/sec^2 also sets minimum segment time in ms (B20000) to prevent buffer under-runs and M20 minimum feedrate
  169. // 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
  170. // M206 - set additional homing offset
  171. // M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop], stays in mm regardless of M200 setting
  172. // M208 - set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/sec]
  173. // 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.
  174. // M218 - set hotend offset (in mm): T<extruder_number> X<offset_on_X> Y<offset_on_Y>
  175. // M220 S<factor in percent>- set speed factor override percentage
  176. // M221 S<factor in percent>- set extrude factor override percentage
  177. // M226 P<pin number> S<pin state>- Wait until the specified pin reaches the state required
  178. // M240 - Trigger a camera to take a photograph
  179. // M250 - Set LCD contrast C<contrast value> (value 0..63)
  180. // M280 - set servo position absolute. P: servo index, S: angle or microseconds
  181. // M300 - Play beep sound S<frequency Hz> P<duration ms>
  182. // M301 - Set PID parameters P I and D
  183. // M302 - Allow cold extrudes, or set the minimum extrude S<temperature>.
  184. // M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
  185. // M304 - Set bed PID parameters P I and D
  186. // M400 - Finish all moves
  187. // M401 - Lower z-probe if present
  188. // M402 - Raise z-probe if present
  189. // M404 - N<dia in mm> Enter the nominal filament width (3mm, 1.75mm ) or will display nominal filament width without parameters
  190. // M405 - Turn on Filament Sensor extrusion control. Optional D<delay in cm> to set delay in centimeters between sensor and extruder
  191. // M406 - Turn off Filament Sensor extrusion control
  192. // M407 - Displays measured filament diameter
  193. // M500 - stores parameters in EEPROM
  194. // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
  195. // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
  196. // M503 - print the current settings (from memory not from EEPROM)
  197. // M509 - force language selection on next restart
  198. // M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
  199. // M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
  200. // M605 - Set dual x-carriage movement mode: S<mode> [ X<duplication x-offset> R<duplication temp offset> ]
  201. // M860 - Wait for PINDA thermistor to reach target temperature.
  202. // M861 - Set / Read PINDA temperature compensation offsets
  203. // M900 - Set LIN_ADVANCE options, if enabled. See Configuration_adv.h for details.
  204. // M907 - Set digital trimpot motor current using axis codes.
  205. // M908 - Control digital trimpot directly.
  206. // M350 - Set microstepping mode.
  207. // M351 - Toggle MS1 MS2 pins directly.
  208. // M928 - Start SD logging (M928 filename.g) - ended by M29
  209. // M999 - Restart after being stopped by error
  210. //Stepper Movement Variables
  211. //===========================================================================
  212. //=============================imported variables============================
  213. //===========================================================================
  214. //===========================================================================
  215. //=============================public variables=============================
  216. //===========================================================================
  217. #ifdef SDSUPPORT
  218. CardReader card;
  219. #endif
  220. unsigned long PingTime = millis();
  221. unsigned long NcTime;
  222. union Data
  223. {
  224. byte b[2];
  225. int value;
  226. };
  227. float homing_feedrate[] = HOMING_FEEDRATE;
  228. // Currently only the extruder axis may be switched to a relative mode.
  229. // Other axes are always absolute or relative based on the common relative_mode flag.
  230. bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
  231. int feedmultiply=100; //100->1 200->2
  232. int saved_feedmultiply;
  233. int extrudemultiply=100; //100->1 200->2
  234. int extruder_multiply[EXTRUDERS] = {100
  235. #if EXTRUDERS > 1
  236. , 100
  237. #if EXTRUDERS > 2
  238. , 100
  239. #endif
  240. #endif
  241. };
  242. int bowden_length[4] = {385, 385, 385, 385};
  243. bool is_usb_printing = false;
  244. bool homing_flag = false;
  245. bool temp_cal_active = false;
  246. unsigned long kicktime = millis()+100000;
  247. unsigned int usb_printing_counter;
  248. int lcd_change_fil_state = 0;
  249. int feedmultiplyBckp = 100;
  250. float HotendTempBckp = 0;
  251. int fanSpeedBckp = 0;
  252. float pause_lastpos[4];
  253. unsigned long pause_time = 0;
  254. unsigned long start_pause_print = millis();
  255. unsigned long t_fan_rising_edge = millis();
  256. //unsigned long load_filament_time;
  257. bool mesh_bed_leveling_flag = false;
  258. bool mesh_bed_run_from_menu = false;
  259. //unsigned char lang_selected = 0;
  260. int8_t FarmMode = 0;
  261. bool prusa_sd_card_upload = false;
  262. unsigned int status_number = 0;
  263. unsigned long total_filament_used;
  264. unsigned int heating_status;
  265. unsigned int heating_status_counter;
  266. bool custom_message;
  267. bool loading_flag = false;
  268. unsigned int custom_message_type;
  269. unsigned int custom_message_state;
  270. char snmm_filaments_used = 0;
  271. bool fan_state[2];
  272. int fan_edge_counter[2];
  273. int fan_speed[2];
  274. char dir_names[3][9];
  275. bool sortAlpha = false;
  276. bool volumetric_enabled = false;
  277. float filament_size[EXTRUDERS] = { DEFAULT_NOMINAL_FILAMENT_DIA
  278. #if EXTRUDERS > 1
  279. , DEFAULT_NOMINAL_FILAMENT_DIA
  280. #if EXTRUDERS > 2
  281. , DEFAULT_NOMINAL_FILAMENT_DIA
  282. #endif
  283. #endif
  284. };
  285. float extruder_multiplier[EXTRUDERS] = {1.0
  286. #if EXTRUDERS > 1
  287. , 1.0
  288. #if EXTRUDERS > 2
  289. , 1.0
  290. #endif
  291. #endif
  292. };
  293. float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 };
  294. float add_homing[3]={0,0,0};
  295. float min_pos[3] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS };
  296. float max_pos[3] = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS };
  297. bool axis_known_position[3] = {false, false, false};
  298. float zprobe_zoffset;
  299. // Extruder offset
  300. #if EXTRUDERS > 1
  301. #define NUM_EXTRUDER_OFFSETS 2 // only in XY plane
  302. float extruder_offset[NUM_EXTRUDER_OFFSETS][EXTRUDERS] = {
  303. #if defined(EXTRUDER_OFFSET_X) && defined(EXTRUDER_OFFSET_Y)
  304. EXTRUDER_OFFSET_X, EXTRUDER_OFFSET_Y
  305. #endif
  306. };
  307. #endif
  308. uint8_t active_extruder = 0;
  309. int fanSpeed=0;
  310. #ifdef FWRETRACT
  311. bool autoretract_enabled=false;
  312. bool retracted[EXTRUDERS]={false
  313. #if EXTRUDERS > 1
  314. , false
  315. #if EXTRUDERS > 2
  316. , false
  317. #endif
  318. #endif
  319. };
  320. bool retracted_swap[EXTRUDERS]={false
  321. #if EXTRUDERS > 1
  322. , false
  323. #if EXTRUDERS > 2
  324. , false
  325. #endif
  326. #endif
  327. };
  328. float retract_length = RETRACT_LENGTH;
  329. float retract_length_swap = RETRACT_LENGTH_SWAP;
  330. float retract_feedrate = RETRACT_FEEDRATE;
  331. float retract_zlift = RETRACT_ZLIFT;
  332. float retract_recover_length = RETRACT_RECOVER_LENGTH;
  333. float retract_recover_length_swap = RETRACT_RECOVER_LENGTH_SWAP;
  334. float retract_recover_feedrate = RETRACT_RECOVER_FEEDRATE;
  335. #endif
  336. #ifdef ULTIPANEL
  337. #ifdef PS_DEFAULT_OFF
  338. bool powersupply = false;
  339. #else
  340. bool powersupply = true;
  341. #endif
  342. #endif
  343. bool cancel_heatup = false ;
  344. #ifdef HOST_KEEPALIVE_FEATURE
  345. int busy_state = NOT_BUSY;
  346. static long prev_busy_signal_ms = -1;
  347. uint8_t host_keepalive_interval = HOST_KEEPALIVE_INTERVAL;
  348. #else
  349. #define host_keepalive();
  350. #define KEEPALIVE_STATE(n);
  351. #endif
  352. const char errormagic[] PROGMEM = "Error:";
  353. const char echomagic[] PROGMEM = "echo:";
  354. bool no_response = false;
  355. uint8_t important_status;
  356. uint8_t saved_filament_type;
  357. //===========================================================================
  358. //=============================Private Variables=============================
  359. //===========================================================================
  360. const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
  361. float destination[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0};
  362. static float delta[3] = {0.0, 0.0, 0.0};
  363. // For tracing an arc
  364. static float offset[3] = {0.0, 0.0, 0.0};
  365. static float feedrate = 1500.0, next_feedrate, saved_feedrate;
  366. // Determines Absolute or Relative Coordinates.
  367. // Also there is bool axis_relative_modes[] per axis flag.
  368. static bool relative_mode = false;
  369. #ifndef _DISABLE_M42_M226
  370. const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42
  371. #endif //_DISABLE_M42_M226
  372. //static float tt = 0;
  373. //static float bt = 0;
  374. //Inactivity shutdown variables
  375. static unsigned long previous_millis_cmd = 0;
  376. unsigned long max_inactive_time = 0;
  377. static unsigned long stepper_inactive_time = DEFAULT_STEPPER_DEACTIVE_TIME*1000l;
  378. unsigned long starttime=0;
  379. unsigned long stoptime=0;
  380. unsigned long _usb_timer = 0;
  381. static uint8_t tmp_extruder;
  382. bool extruder_under_pressure = true;
  383. bool Stopped=false;
  384. #if NUM_SERVOS > 0
  385. Servo servos[NUM_SERVOS];
  386. #endif
  387. bool CooldownNoWait = true;
  388. bool target_direction;
  389. //Insert variables if CHDK is defined
  390. #ifdef CHDK
  391. unsigned long chdkHigh = 0;
  392. boolean chdkActive = false;
  393. #endif
  394. //===========================================================================
  395. //=============================Routines======================================
  396. //===========================================================================
  397. void get_arc_coordinates();
  398. bool setTargetedHotend(int code);
  399. void serial_echopair_P(const char *s_P, float v)
  400. { serialprintPGM(s_P); SERIAL_ECHO(v); }
  401. void serial_echopair_P(const char *s_P, double v)
  402. { serialprintPGM(s_P); SERIAL_ECHO(v); }
  403. void serial_echopair_P(const char *s_P, unsigned long v)
  404. { serialprintPGM(s_P); SERIAL_ECHO(v); }
  405. #ifdef SDSUPPORT
  406. #include "SdFatUtil.h"
  407. int freeMemory() { return SdFatUtil::FreeRam(); }
  408. #else
  409. extern "C" {
  410. extern unsigned int __bss_end;
  411. extern unsigned int __heap_start;
  412. extern void *__brkval;
  413. int freeMemory() {
  414. int free_memory;
  415. if ((int)__brkval == 0)
  416. free_memory = ((int)&free_memory) - ((int)&__bss_end);
  417. else
  418. free_memory = ((int)&free_memory) - ((int)__brkval);
  419. return free_memory;
  420. }
  421. }
  422. #endif //!SDSUPPORT
  423. void setup_killpin()
  424. {
  425. #if defined(KILL_PIN) && KILL_PIN > -1
  426. SET_INPUT(KILL_PIN);
  427. WRITE(KILL_PIN,HIGH);
  428. #endif
  429. }
  430. // Set home pin
  431. void setup_homepin(void)
  432. {
  433. #if defined(HOME_PIN) && HOME_PIN > -1
  434. SET_INPUT(HOME_PIN);
  435. WRITE(HOME_PIN,HIGH);
  436. #endif
  437. }
  438. void setup_photpin()
  439. {
  440. #if defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1
  441. SET_OUTPUT(PHOTOGRAPH_PIN);
  442. WRITE(PHOTOGRAPH_PIN, LOW);
  443. #endif
  444. }
  445. void setup_powerhold()
  446. {
  447. #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
  448. SET_OUTPUT(SUICIDE_PIN);
  449. WRITE(SUICIDE_PIN, HIGH);
  450. #endif
  451. #if defined(PS_ON_PIN) && PS_ON_PIN > -1
  452. SET_OUTPUT(PS_ON_PIN);
  453. #if defined(PS_DEFAULT_OFF)
  454. WRITE(PS_ON_PIN, PS_ON_ASLEEP);
  455. #else
  456. WRITE(PS_ON_PIN, PS_ON_AWAKE);
  457. #endif
  458. #endif
  459. }
  460. void suicide()
  461. {
  462. #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
  463. SET_OUTPUT(SUICIDE_PIN);
  464. WRITE(SUICIDE_PIN, LOW);
  465. #endif
  466. }
  467. void servo_init()
  468. {
  469. #if (NUM_SERVOS >= 1) && defined(SERVO0_PIN) && (SERVO0_PIN > -1)
  470. servos[0].attach(SERVO0_PIN);
  471. #endif
  472. #if (NUM_SERVOS >= 2) && defined(SERVO1_PIN) && (SERVO1_PIN > -1)
  473. servos[1].attach(SERVO1_PIN);
  474. #endif
  475. #if (NUM_SERVOS >= 3) && defined(SERVO2_PIN) && (SERVO2_PIN > -1)
  476. servos[2].attach(SERVO2_PIN);
  477. #endif
  478. #if (NUM_SERVOS >= 4) && defined(SERVO3_PIN) && (SERVO3_PIN > -1)
  479. servos[3].attach(SERVO3_PIN);
  480. #endif
  481. #if (NUM_SERVOS >= 5)
  482. #error "TODO: enter initalisation code for more servos"
  483. #endif
  484. }
  485. static void lcd_language_menu();
  486. void stop_and_save_print_to_ram(float z_move, float e_move);
  487. void restore_print_from_ram_and_continue(float e_move);
  488. bool fans_check_enabled = true;
  489. bool filament_autoload_enabled = true;
  490. #ifdef TMC2130
  491. extern int8_t CrashDetectMenu;
  492. void crashdet_enable()
  493. {
  494. // MYSERIAL.println("crashdet_enable");
  495. tmc2130_sg_stop_on_crash = true;
  496. eeprom_update_byte((uint8_t*)EEPROM_CRASH_DET, 0xFF);
  497. CrashDetectMenu = 1;
  498. }
  499. void crashdet_disable()
  500. {
  501. // MYSERIAL.println("crashdet_disable");
  502. tmc2130_sg_stop_on_crash = false;
  503. tmc2130_sg_crash = 0;
  504. eeprom_update_byte((uint8_t*)EEPROM_CRASH_DET, 0x00);
  505. CrashDetectMenu = 0;
  506. }
  507. void crashdet_stop_and_save_print()
  508. {
  509. stop_and_save_print_to_ram(10, 0); //XY - no change, Z 10mm up, E - no change
  510. }
  511. void crashdet_restore_print_and_continue()
  512. {
  513. restore_print_from_ram_and_continue(0); //XYZ = orig, E - no change
  514. // babystep_apply();
  515. }
  516. void crashdet_stop_and_save_print2()
  517. {
  518. cli();
  519. planner_abort_hard(); //abort printing
  520. cmdqueue_reset(); //empty cmdqueue
  521. card.sdprinting = false;
  522. card.closefile();
  523. // Reset and re-enable the stepper timer just before the global interrupts are enabled.
  524. st_reset_timer();
  525. sei();
  526. }
  527. void crashdet_detected(uint8_t mask)
  528. {
  529. // printf("CRASH_DETECTED");
  530. /* while (!is_buffer_empty())
  531. {
  532. process_commands();
  533. cmdqueue_pop_front();
  534. }*/
  535. st_synchronize();
  536. lcd_update_enable(true);
  537. lcd_implementation_clear();
  538. lcd_update(2);
  539. if (mask & X_AXIS_MASK)
  540. {
  541. eeprom_update_byte((uint8_t*)EEPROM_CRASH_COUNT_X, eeprom_read_byte((uint8_t*)EEPROM_CRASH_COUNT_X) + 1);
  542. eeprom_update_word((uint16_t*)EEPROM_CRASH_COUNT_X_TOT, eeprom_read_word((uint16_t*)EEPROM_CRASH_COUNT_X_TOT) + 1);
  543. }
  544. if (mask & Y_AXIS_MASK)
  545. {
  546. eeprom_update_byte((uint8_t*)EEPROM_CRASH_COUNT_Y, eeprom_read_byte((uint8_t*)EEPROM_CRASH_COUNT_Y) + 1);
  547. eeprom_update_word((uint16_t*)EEPROM_CRASH_COUNT_Y_TOT, eeprom_read_word((uint16_t*)EEPROM_CRASH_COUNT_Y_TOT) + 1);
  548. }
  549. #ifdef AUTOMATIC_RECOVERY_AFTER_CRASH
  550. bool yesno = true;
  551. #else
  552. bool yesno = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_CRASH_DETECTED), false);
  553. #endif
  554. lcd_update_enable(true);
  555. lcd_update(2);
  556. lcd_setstatuspgm(_T(MSG_CRASH_DETECTED));
  557. if (yesno)
  558. {
  559. enquecommand_P(PSTR("G28 X Y"));
  560. enquecommand_P(PSTR("CRASH_RECOVER"));
  561. }
  562. else
  563. {
  564. enquecommand_P(PSTR("CRASH_CANCEL"));
  565. }
  566. }
  567. void crashdet_recover()
  568. {
  569. crashdet_restore_print_and_continue();
  570. tmc2130_sg_stop_on_crash = true;
  571. }
  572. void crashdet_cancel()
  573. {
  574. card.sdprinting = false;
  575. card.closefile();
  576. tmc2130_sg_stop_on_crash = true;
  577. }
  578. #endif //TMC2130
  579. void failstats_reset_print()
  580. {
  581. eeprom_update_byte((uint8_t *)EEPROM_CRASH_COUNT_X, 0);
  582. eeprom_update_byte((uint8_t *)EEPROM_CRASH_COUNT_Y, 0);
  583. eeprom_update_byte((uint8_t *)EEPROM_FERROR_COUNT, 0);
  584. eeprom_update_byte((uint8_t *)EEPROM_POWER_COUNT, 0);
  585. }
  586. #ifdef MESH_BED_LEVELING
  587. enum MeshLevelingState { MeshReport, MeshStart, MeshNext, MeshSet };
  588. #endif
  589. // Factory reset function
  590. // This function is used to erase parts or whole EEPROM memory which is used for storing calibration and and so on.
  591. // Level input parameter sets depth of reset
  592. // Quiet parameter masks all waitings for user interact.
  593. int er_progress = 0;
  594. void factory_reset(char level, bool quiet)
  595. {
  596. lcd_implementation_clear();
  597. int cursor_pos = 0;
  598. switch (level) {
  599. // Level 0: Language reset
  600. case 0:
  601. WRITE(BEEPER, HIGH);
  602. _delay_ms(100);
  603. WRITE(BEEPER, LOW);
  604. lcd_force_language_selection();
  605. break;
  606. //Level 1: Reset statistics
  607. case 1:
  608. WRITE(BEEPER, HIGH);
  609. _delay_ms(100);
  610. WRITE(BEEPER, LOW);
  611. eeprom_update_dword((uint32_t *)EEPROM_TOTALTIME, 0);
  612. eeprom_update_dword((uint32_t *)EEPROM_FILAMENTUSED, 0);
  613. eeprom_update_byte((uint8_t *)EEPROM_CRASH_COUNT_X, 0);
  614. eeprom_update_byte((uint8_t *)EEPROM_CRASH_COUNT_Y, 0);
  615. eeprom_update_byte((uint8_t *)EEPROM_FERROR_COUNT, 0);
  616. eeprom_update_byte((uint8_t *)EEPROM_POWER_COUNT, 0);
  617. eeprom_update_word((uint16_t *)EEPROM_CRASH_COUNT_X_TOT, 0);
  618. eeprom_update_word((uint16_t *)EEPROM_CRASH_COUNT_Y_TOT, 0);
  619. eeprom_update_word((uint16_t *)EEPROM_FERROR_COUNT_TOT, 0);
  620. eeprom_update_word((uint16_t *)EEPROM_POWER_COUNT_TOT, 0);
  621. lcd_menu_statistics();
  622. break;
  623. // Level 2: Prepare for shipping
  624. case 2:
  625. //lcd_printPGM(PSTR("Factory RESET"));
  626. //lcd_print_at_PGM(1,2,PSTR("Shipping prep"));
  627. // Force language selection at the next boot up.
  628. lcd_force_language_selection();
  629. // Force the "Follow calibration flow" message at the next boot up.
  630. calibration_status_store(CALIBRATION_STATUS_Z_CALIBRATION);
  631. eeprom_write_byte((uint8_t*)EEPROM_WIZARD_ACTIVE, 1); //run wizard
  632. farm_no = 0;
  633. //*** MaR::180501_01
  634. farm_mode = false;
  635. eeprom_update_byte((uint8_t*)EEPROM_FARM_MODE, farm_mode);
  636. EEPROM_save_B(EEPROM_FARM_NUMBER, &farm_no);
  637. WRITE(BEEPER, HIGH);
  638. _delay_ms(100);
  639. WRITE(BEEPER, LOW);
  640. //_delay_ms(2000);
  641. break;
  642. // Level 3: erase everything, whole EEPROM will be set to 0xFF
  643. case 3:
  644. lcd_printPGM(PSTR("Factory RESET"));
  645. lcd_print_at_PGM(1, 2, PSTR("ERASING all data"));
  646. WRITE(BEEPER, HIGH);
  647. _delay_ms(100);
  648. WRITE(BEEPER, LOW);
  649. er_progress = 0;
  650. lcd_print_at_PGM(3, 3, PSTR(" "));
  651. lcd_implementation_print_at(3, 3, er_progress);
  652. // Erase EEPROM
  653. for (int i = 0; i < 4096; i++) {
  654. eeprom_write_byte((uint8_t*)i, 0xFF);
  655. if (i % 41 == 0) {
  656. er_progress++;
  657. lcd_print_at_PGM(3, 3, PSTR(" "));
  658. lcd_implementation_print_at(3, 3, er_progress);
  659. lcd_printPGM(PSTR("%"));
  660. }
  661. }
  662. break;
  663. case 4:
  664. bowden_menu();
  665. break;
  666. default:
  667. break;
  668. }
  669. }
  670. #include "LiquidCrystal_Prusa.h"
  671. extern LiquidCrystal_Prusa lcd;
  672. FILE _lcdout = {0};
  673. int lcd_putchar(char c, FILE *stream)
  674. {
  675. lcd.write(c);
  676. return 0;
  677. }
  678. FILE _uartout = {0};
  679. int uart_putchar(char c, FILE *stream)
  680. {
  681. MYSERIAL.write(c);
  682. return 0;
  683. }
  684. void lcd_splash()
  685. {
  686. // lcd_print_at_PGM(0, 1, PSTR(" Original Prusa "));
  687. // lcd_print_at_PGM(0, 2, PSTR(" 3D Printers "));
  688. // lcd.print_P(PSTR("\x1b[1;3HOriginal Prusa\x1b[2;4H3D Printers"));
  689. fputs_P(PSTR(ESC_2J ESC_H(1,1) "Original Prusa i3" ESC_H(3,2) "Prusa Research"), lcdout);
  690. }
  691. void factory_reset()
  692. {
  693. KEEPALIVE_STATE(PAUSED_FOR_USER);
  694. if (!READ(BTN_ENC))
  695. {
  696. _delay_ms(1000);
  697. if (!READ(BTN_ENC))
  698. {
  699. lcd_implementation_clear();
  700. lcd_printPGM(PSTR("Factory RESET"));
  701. SET_OUTPUT(BEEPER);
  702. WRITE(BEEPER, HIGH);
  703. while (!READ(BTN_ENC));
  704. WRITE(BEEPER, LOW);
  705. _delay_ms(2000);
  706. char level = reset_menu();
  707. factory_reset(level, false);
  708. switch (level) {
  709. case 0: _delay_ms(0); break;
  710. case 1: _delay_ms(0); break;
  711. case 2: _delay_ms(0); break;
  712. case 3: _delay_ms(0); break;
  713. }
  714. // _delay_ms(100);
  715. /*
  716. #ifdef MESH_BED_LEVELING
  717. _delay_ms(2000);
  718. if (!READ(BTN_ENC))
  719. {
  720. WRITE(BEEPER, HIGH);
  721. _delay_ms(100);
  722. WRITE(BEEPER, LOW);
  723. _delay_ms(200);
  724. WRITE(BEEPER, HIGH);
  725. _delay_ms(100);
  726. WRITE(BEEPER, LOW);
  727. int _z = 0;
  728. calibration_status_store(CALIBRATION_STATUS_CALIBRATED);
  729. EEPROM_save_B(EEPROM_BABYSTEP_X, &_z);
  730. EEPROM_save_B(EEPROM_BABYSTEP_Y, &_z);
  731. EEPROM_save_B(EEPROM_BABYSTEP_Z, &_z);
  732. }
  733. else
  734. {
  735. WRITE(BEEPER, HIGH);
  736. _delay_ms(100);
  737. WRITE(BEEPER, LOW);
  738. }
  739. #endif // mesh */
  740. }
  741. }
  742. else
  743. {
  744. //_delay_ms(1000); // wait 1sec to display the splash screen // what's this and why do we need it?? - andre
  745. }
  746. KEEPALIVE_STATE(IN_HANDLER);
  747. }
  748. void show_fw_version_warnings() {
  749. if (FW_DEV_VERSION == FW_VERSION_GOLD || FW_DEV_VERSION == FW_VERSION_RC) return;
  750. switch (FW_DEV_VERSION) {
  751. case(FW_VERSION_ALPHA): lcd_show_fullscreen_message_and_wait_P(_i("You are using firmware alpha version. This is development version. Using this version is not recommended and may cause printer damage.")); break;////MSG_FW_VERSION_ALPHA c=20 r=8
  752. case(FW_VERSION_BETA): lcd_show_fullscreen_message_and_wait_P(_i("You are using firmware beta version. This is development version. Using this version is not recommended and may cause printer damage.")); break;////MSG_FW_VERSION_BETA c=20 r=8
  753. case(FW_VERSION_DEVEL):
  754. case(FW_VERSION_DEBUG):
  755. lcd_update_enable(false);
  756. lcd_implementation_clear();
  757. #if FW_DEV_VERSION == FW_VERSION_DEVEL
  758. lcd_print_at_PGM(0, 0, PSTR("Development build !!"));
  759. #else
  760. lcd_print_at_PGM(0, 0, PSTR("Debbugging build !!!"));
  761. #endif
  762. lcd_print_at_PGM(0, 1, PSTR("May destroy printer!"));
  763. lcd_print_at_PGM(0, 2, PSTR("ver ")); lcd_printPGM(PSTR(FW_VERSION_FULL));
  764. lcd_print_at_PGM(0, 3, PSTR(FW_REPOSITORY));
  765. lcd_wait_for_click();
  766. break;
  767. default: lcd_show_fullscreen_message_and_wait_P(_i("WARNING: This is an unofficial, unsupported build. Use at your own risk!")); break;////MSG_FW_VERSION_UNKNOWN c=20 r=8
  768. }
  769. lcd_update_enable(true);
  770. }
  771. uint8_t check_printer_version()
  772. {
  773. uint8_t version_changed = 0;
  774. uint16_t printer_type = eeprom_read_word((uint16_t*)EEPROM_PRINTER_TYPE);
  775. uint16_t motherboard = eeprom_read_word((uint16_t*)EEPROM_BOARD_TYPE);
  776. if (printer_type != PRINTER_TYPE) {
  777. if (printer_type == 0xffff) eeprom_write_word((uint16_t*)EEPROM_PRINTER_TYPE, PRINTER_TYPE);
  778. else version_changed |= 0b10;
  779. }
  780. if (motherboard != MOTHERBOARD) {
  781. if(motherboard == 0xffff) eeprom_write_word((uint16_t*)EEPROM_BOARD_TYPE, MOTHERBOARD);
  782. else version_changed |= 0b01;
  783. }
  784. return version_changed;
  785. }
  786. void erase_eeprom_section(uint16_t offset, uint16_t bytes)
  787. {
  788. for (int i = offset; i < (offset+bytes); i++) eeprom_write_byte((uint8_t*)i, 0xFF);
  789. }
  790. // "Setup" function is called by the Arduino framework on startup.
  791. // Before startup, the Timers-functions (PWM)/Analog RW and HardwareSerial provided by the Arduino-code
  792. // are initialized by the main() routine provided by the Arduino framework.
  793. void setup()
  794. {
  795. lcd_init();
  796. fdev_setup_stream(lcdout, lcd_putchar, NULL, _FDEV_SETUP_WRITE); //setup lcdout stream
  797. lcd_splash();
  798. setup_killpin();
  799. setup_powerhold();
  800. //*** MaR::180501_02b
  801. farm_mode = eeprom_read_byte((uint8_t*)EEPROM_FARM_MODE);
  802. EEPROM_read_B(EEPROM_FARM_NUMBER, &farm_no);
  803. if ((farm_mode == 0xFF && farm_no == 0) || ((uint16_t)farm_no == 0xFFFF))
  804. farm_mode = false; //if farm_mode has not been stored to eeprom yet and farm number is set to zero or EEPROM is fresh, deactivate farm mode
  805. if ((uint16_t)farm_no == 0xFFFF) farm_no = 0;
  806. selectedSerialPort = eeprom_read_byte((uint8_t*)EEPROM_SECOND_SERIAL_ACTIVE);
  807. if (selectedSerialPort == 0xFF) selectedSerialPort = 0;
  808. if (farm_mode)
  809. {
  810. no_response = true; //we need confirmation by recieving PRUSA thx
  811. important_status = 8;
  812. prusa_statistics(8);
  813. selectedSerialPort = 1;
  814. }
  815. MYSERIAL.begin(BAUDRATE);
  816. fdev_setup_stream(uartout, uart_putchar, NULL, _FDEV_SETUP_WRITE); //setup uart out stream
  817. stdout = uartout;
  818. SERIAL_PROTOCOLLNPGM("start");
  819. SERIAL_ECHO_START;
  820. printf_P(PSTR(" "FW_VERSION_FULL"\n"));
  821. #if 0
  822. SERIAL_ECHOLN("Reading eeprom from 0 to 100: start");
  823. for (int i = 0; i < 4096; ++i) {
  824. int b = eeprom_read_byte((unsigned char*)i);
  825. if (b != 255) {
  826. SERIAL_ECHO(i);
  827. SERIAL_ECHO(":");
  828. SERIAL_ECHO(b);
  829. SERIAL_ECHOLN("");
  830. }
  831. }
  832. SERIAL_ECHOLN("Reading eeprom from 0 to 100: done");
  833. #endif
  834. // Check startup - does nothing if bootloader sets MCUSR to 0
  835. byte mcu = MCUSR;
  836. /* if (mcu & 1) SERIAL_ECHOLNRPGM(_T(MSG_POWERUP));
  837. if (mcu & 2) SERIAL_ECHOLNRPGM(MSG_EXTERNAL_RESET);
  838. if (mcu & 4) SERIAL_ECHOLNRPGM(MSG_BROWNOUT_RESET);
  839. if (mcu & 8) SERIAL_ECHOLNRPGM(MSG_WATCHDOG_RESET);
  840. if (mcu & 32) SERIAL_ECHOLNRPGM(MSG_SOFTWARE_RESET);*/
  841. if (mcu & 1) puts_P(_T(MSG_POWERUP));
  842. if (mcu & 2) puts_P(MSG_EXTERNAL_RESET);
  843. if (mcu & 4) puts_P(MSG_BROWNOUT_RESET);
  844. if (mcu & 8) puts_P(MSG_WATCHDOG_RESET);
  845. if (mcu & 32) puts_P(MSG_SOFTWARE_RESET);
  846. MCUSR = 0;
  847. //SERIAL_ECHORPGM(MSG_MARLIN);
  848. //SERIAL_ECHOLNRPGM(VERSION_STRING);
  849. #ifdef STRING_VERSION_CONFIG_H
  850. #ifdef STRING_CONFIG_H_AUTHOR
  851. SERIAL_ECHO_START;
  852. SERIAL_ECHORPGM(_i(" Last Updated: "));////MSG_CONFIGURATION_VER c=0 r=0
  853. SERIAL_ECHOPGM(STRING_VERSION_CONFIG_H);
  854. SERIAL_ECHORPGM(_n(" | Author: "));////MSG_AUTHOR c=0 r=0
  855. SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR);
  856. SERIAL_ECHOPGM("Compiled: ");
  857. SERIAL_ECHOLNPGM(__DATE__);
  858. #endif
  859. #endif
  860. SERIAL_ECHO_START;
  861. SERIAL_ECHORPGM(_i(" Free Memory: "));////MSG_FREE_MEMORY c=0 r=0
  862. SERIAL_ECHO(freeMemory());
  863. SERIAL_ECHORPGM(_i(" PlannerBufferBytes: "));////MSG_PLANNER_BUFFER_BYTES c=0 r=0
  864. SERIAL_ECHOLN((int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
  865. //lcd_update_enable(false); // why do we need this?? - andre
  866. // loads data from EEPROM if available else uses defaults (and resets step acceleration rate)
  867. bool previous_settings_retrieved = false;
  868. uint8_t hw_changed = check_printer_version();
  869. if (!(hw_changed & 0b10)) { //if printer version wasn't changed, check for eeprom version and retrieve settings from eeprom in case that version wasn't changed
  870. previous_settings_retrieved = Config_RetrieveSettings(EEPROM_OFFSET);
  871. }
  872. else { //printer version was changed so use default settings
  873. Config_ResetDefault();
  874. }
  875. SdFatUtil::set_stack_guard(); //writes magic number at the end of static variables to protect against overwriting static memory by stack
  876. tp_init(); // Initialize temperature loop
  877. lcd_splash(); // we need to do this again, because tp_init() kills lcd
  878. plan_init(); // Initialize planner;
  879. factory_reset();
  880. #ifdef TMC2130
  881. uint8_t silentMode = eeprom_read_byte((uint8_t*)EEPROM_SILENT);
  882. if (silentMode == 0xff) silentMode = 0;
  883. // tmc2130_mode = silentMode?TMC2130_MODE_SILENT:TMC2130_MODE_NORMAL;
  884. tmc2130_mode = TMC2130_MODE_NORMAL;
  885. uint8_t crashdet = eeprom_read_byte((uint8_t*)EEPROM_CRASH_DET);
  886. if (crashdet && !farm_mode)
  887. {
  888. crashdet_enable();
  889. MYSERIAL.println("CrashDetect ENABLED!");
  890. }
  891. else
  892. {
  893. crashdet_disable();
  894. MYSERIAL.println("CrashDetect DISABLED");
  895. }
  896. #ifdef TMC2130_LINEARITY_CORRECTION
  897. #ifdef EXPERIMENTAL_FEATURES
  898. tmc2130_wave_fac[X_AXIS] = eeprom_read_word((uint8_t*)EEPROM_TMC2130_WAVE_X_FAC);
  899. tmc2130_wave_fac[Y_AXIS] = eeprom_read_word((uint8_t*)EEPROM_TMC2130_WAVE_Y_FAC);
  900. tmc2130_wave_fac[Z_AXIS] = eeprom_read_word((uint8_t*)EEPROM_TMC2130_WAVE_Z_FAC);
  901. #endif //EXPERIMENTAL_FEATURES
  902. tmc2130_wave_fac[E_AXIS] = eeprom_read_word((uint16_t*)EEPROM_TMC2130_WAVE_E_FAC);
  903. if (tmc2130_wave_fac[X_AXIS] == 0xff) tmc2130_wave_fac[X_AXIS] = 0;
  904. if (tmc2130_wave_fac[Y_AXIS] == 0xff) tmc2130_wave_fac[Y_AXIS] = 0;
  905. if (tmc2130_wave_fac[Z_AXIS] == 0xff) tmc2130_wave_fac[Z_AXIS] = 0;
  906. if (tmc2130_wave_fac[E_AXIS] == 0xff) tmc2130_wave_fac[E_AXIS] = 0;
  907. #endif //TMC2130_LINEARITY_CORRECTION
  908. #ifdef TMC2130_VARIABLE_RESOLUTION
  909. tmc2130_mres[X_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_X_MRES);
  910. tmc2130_mres[Y_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_Y_MRES);
  911. tmc2130_mres[Z_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_Z_MRES);
  912. tmc2130_mres[E_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_E_MRES);
  913. if (tmc2130_mres[X_AXIS] == 0xff) tmc2130_mres[X_AXIS] = tmc2130_usteps2mres(TMC2130_USTEPS_XY);
  914. if (tmc2130_mres[Y_AXIS] == 0xff) tmc2130_mres[Y_AXIS] = tmc2130_usteps2mres(TMC2130_USTEPS_XY);
  915. if (tmc2130_mres[Z_AXIS] == 0xff) tmc2130_mres[Z_AXIS] = tmc2130_usteps2mres(TMC2130_USTEPS_Z);
  916. if (tmc2130_mres[E_AXIS] == 0xff) tmc2130_mres[E_AXIS] = tmc2130_usteps2mres(TMC2130_USTEPS_E);
  917. eeprom_update_byte((uint8_t*)EEPROM_TMC2130_X_MRES, tmc2130_mres[X_AXIS]);
  918. eeprom_update_byte((uint8_t*)EEPROM_TMC2130_Y_MRES, tmc2130_mres[Y_AXIS]);
  919. eeprom_update_byte((uint8_t*)EEPROM_TMC2130_Z_MRES, tmc2130_mres[Z_AXIS]);
  920. eeprom_update_byte((uint8_t*)EEPROM_TMC2130_E_MRES, tmc2130_mres[E_AXIS]);
  921. #else //TMC2130_VARIABLE_RESOLUTION
  922. tmc2130_mres[X_AXIS] = tmc2130_usteps2mres(TMC2130_USTEPS_XY);
  923. tmc2130_mres[Y_AXIS] = tmc2130_usteps2mres(TMC2130_USTEPS_XY);
  924. tmc2130_mres[Z_AXIS] = tmc2130_usteps2mres(TMC2130_USTEPS_Z);
  925. tmc2130_mres[E_AXIS] = tmc2130_usteps2mres(TMC2130_USTEPS_E);
  926. #endif //TMC2130_VARIABLE_RESOLUTION
  927. #endif //TMC2130
  928. #ifdef NEW_SPI
  929. spi_init();
  930. #endif //NEW_SPI
  931. st_init(); // Initialize stepper, this enables interrupts!
  932. #ifdef TMC2130
  933. tmc2130_mode = silentMode?TMC2130_MODE_SILENT:TMC2130_MODE_NORMAL;
  934. tmc2130_init();
  935. #endif //TMC2130
  936. setup_photpin();
  937. servo_init();
  938. // Reset the machine correction matrix.
  939. // It does not make sense to load the correction matrix until the machine is homed.
  940. world2machine_reset();
  941. #ifdef PAT9125
  942. fsensor_init();
  943. #endif //PAT9125
  944. #if defined(CONTROLLERFAN_PIN) && (CONTROLLERFAN_PIN > -1)
  945. SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
  946. #endif
  947. setup_homepin();
  948. #ifdef TMC2130
  949. if (1) {
  950. /// SERIAL_ECHOPGM("initial zsteps on power up: "); MYSERIAL.println(tmc2130_rd_MSCNT(Z_AXIS));
  951. // try to run to zero phase before powering the Z motor.
  952. // Move in negative direction
  953. WRITE(Z_DIR_PIN,INVERT_Z_DIR);
  954. // Round the current micro-micro steps to micro steps.
  955. for (uint16_t phase = (tmc2130_rd_MSCNT(Z_AXIS) + 8) >> 4; phase > 0; -- phase) {
  956. // Until the phase counter is reset to zero.
  957. WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
  958. delay(2);
  959. WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN);
  960. delay(2);
  961. }
  962. // SERIAL_ECHOPGM("initial zsteps after reset: "); MYSERIAL.println(tmc2130_rd_MSCNT(Z_AXIS));
  963. }
  964. #endif //TMC2130
  965. #if defined(Z_AXIS_ALWAYS_ON)
  966. enable_z();
  967. #endif
  968. //*** MaR::180501_02
  969. farm_mode = eeprom_read_byte((uint8_t*)EEPROM_FARM_MODE);
  970. EEPROM_read_B(EEPROM_FARM_NUMBER, &farm_no);
  971. if ((farm_mode == 0xFF && farm_no == 0) || (farm_no == 0xFFFF)) farm_mode = false; //if farm_mode has not been stored to eeprom yet and farm number is set to zero or EEPROM is fresh, deactivate farm mode
  972. if (farm_no == 0xFFFF) farm_no = 0;
  973. if (farm_mode)
  974. {
  975. prusa_statistics(8);
  976. }
  977. // Enable Toshiba FlashAir SD card / WiFi enahanced card.
  978. card.ToshibaFlashAir_enable(eeprom_read_byte((unsigned char*)EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY) == 1);
  979. if (eeprom_read_dword((uint32_t*)(EEPROM_TOP - 4)) == 0x0ffffffff &&
  980. eeprom_read_dword((uint32_t*)(EEPROM_TOP - 8)) == 0x0ffffffff) {
  981. // Maiden startup. The firmware has been loaded and first started on a virgin RAMBo board,
  982. // where all the EEPROM entries are set to 0x0ff.
  983. // Once a firmware boots up, it forces at least a language selection, which changes
  984. // EEPROM_LANG to number lower than 0x0ff.
  985. // 1) Set a high power mode.
  986. #ifdef TMC2130
  987. eeprom_write_byte((uint8_t*)EEPROM_SILENT, 0);
  988. tmc2130_mode = TMC2130_MODE_NORMAL;
  989. #endif //TMC2130
  990. eeprom_write_byte((uint8_t*)EEPROM_WIZARD_ACTIVE, 1); //run wizard
  991. }
  992. // Force SD card update. Otherwise the SD card update is done from loop() on card.checkautostart(false),
  993. // but this times out if a blocking dialog is shown in setup().
  994. card.initsd();
  995. #ifdef DEBUG_SD_SPEED_TEST
  996. if (card.cardOK)
  997. {
  998. uint8_t* buff = (uint8_t*)block_buffer;
  999. uint32_t block = 0;
  1000. uint32_t sumr = 0;
  1001. uint32_t sumw = 0;
  1002. for (int i = 0; i < 1024; i++)
  1003. {
  1004. uint32_t u = micros();
  1005. bool res = card.card.readBlock(i, buff);
  1006. u = micros() - u;
  1007. if (res)
  1008. {
  1009. printf_P(PSTR("readBlock %4d 512 bytes %lu us\n"), i, u);
  1010. sumr += u;
  1011. u = micros();
  1012. res = card.card.writeBlock(i, buff);
  1013. u = micros() - u;
  1014. if (res)
  1015. {
  1016. printf_P(PSTR("writeBlock %4d 512 bytes %lu us\n"), i, u);
  1017. sumw += u;
  1018. }
  1019. else
  1020. {
  1021. printf_P(PSTR("writeBlock %4d error\n"), i);
  1022. break;
  1023. }
  1024. }
  1025. else
  1026. {
  1027. printf_P(PSTR("readBlock %4d error\n"), i);
  1028. break;
  1029. }
  1030. }
  1031. uint32_t avg_rspeed = (1024 * 1000000) / (sumr / 512);
  1032. uint32_t avg_wspeed = (1024 * 1000000) / (sumw / 512);
  1033. printf_P(PSTR("avg read speed %lu bytes/s\n"), avg_rspeed);
  1034. printf_P(PSTR("avg write speed %lu bytes/s\n"), avg_wspeed);
  1035. }
  1036. else
  1037. printf_P(PSTR("Card NG!\n"));
  1038. #endif DEBUG_SD_SPEED_TEST
  1039. if (eeprom_read_byte((uint8_t*)EEPROM_POWER_COUNT) == 0xff) eeprom_write_byte((uint8_t*)EEPROM_POWER_COUNT, 0);
  1040. if (eeprom_read_byte((uint8_t*)EEPROM_CRASH_COUNT_X) == 0xff) eeprom_write_byte((uint8_t*)EEPROM_CRASH_COUNT_X, 0);
  1041. if (eeprom_read_byte((uint8_t*)EEPROM_CRASH_COUNT_Y) == 0xff) eeprom_write_byte((uint8_t*)EEPROM_CRASH_COUNT_Y, 0);
  1042. if (eeprom_read_byte((uint8_t*)EEPROM_FERROR_COUNT) == 0xff) eeprom_write_byte((uint8_t*)EEPROM_FERROR_COUNT, 0);
  1043. if (eeprom_read_word((uint16_t*)EEPROM_POWER_COUNT_TOT) == 0xffff) eeprom_write_word((uint16_t*)EEPROM_POWER_COUNT_TOT, 0);
  1044. if (eeprom_read_word((uint16_t*)EEPROM_CRASH_COUNT_X_TOT) == 0xffff) eeprom_write_word((uint16_t*)EEPROM_CRASH_COUNT_X_TOT, 0);
  1045. if (eeprom_read_word((uint16_t*)EEPROM_CRASH_COUNT_Y_TOT) == 0xffff) eeprom_write_word((uint16_t*)EEPROM_CRASH_COUNT_Y_TOT, 0);
  1046. if (eeprom_read_word((uint16_t*)EEPROM_FERROR_COUNT_TOT) == 0xffff) eeprom_write_word((uint16_t*)EEPROM_FERROR_COUNT_TOT, 0);
  1047. #ifdef SNMM
  1048. if (eeprom_read_dword((uint32_t*)EEPROM_BOWDEN_LENGTH) == 0x0ffffffff) { //bowden length used for SNMM
  1049. int _z = BOWDEN_LENGTH;
  1050. for(int i = 0; i<4; i++) EEPROM_save_B(EEPROM_BOWDEN_LENGTH + i * 2, &_z);
  1051. }
  1052. #endif
  1053. // In the future, somewhere here would one compare the current firmware version against the firmware version stored in the EEPROM.
  1054. // If they differ, an update procedure may need to be performed. At the end of this block, the current firmware version
  1055. // is being written into the EEPROM, so the update procedure will be triggered only once.
  1056. /// lang_selected = eeprom_read_byte((uint8_t*)EEPROM_LANG);
  1057. /// if (lang_selected >= LANG_NUM){
  1058. /// lcd_mylang();
  1059. /// }
  1060. lang_select(1);
  1061. puts_P(_n("\nNew ML support"));
  1062. printf_P(_n(" lang_selected = %d\n"), lang_selected);
  1063. printf_P(_n(" &_SEC_LANG = 0x%04x\n"), &_SEC_LANG);
  1064. printf_P(_n(" sizeof(_SEC_LANG) = 0x%04x\n"), sizeof(_SEC_LANG));
  1065. uint16_t ptr_lang_table0 = ((uint16_t)(&_SEC_LANG) + 0xff) & 0xff00;
  1066. printf_P(_n(" &_lang_table0 = 0x%04x\n"), ptr_lang_table0);
  1067. uint32_t _lt_magic = pgm_read_dword(((uint32_t*)(ptr_lang_table0 + 0)));
  1068. uint16_t _lt_size = pgm_read_word(((uint16_t*)(ptr_lang_table0 + 4)));
  1069. uint16_t _lt_count = pgm_read_word(((uint16_t*)(ptr_lang_table0 + 6)));
  1070. uint16_t _lt_chsum = pgm_read_word(((uint16_t*)(ptr_lang_table0 + 8)));
  1071. uint16_t _lt_resv0 = pgm_read_word(((uint16_t*)(ptr_lang_table0 + 10)));
  1072. uint32_t _lt_resv1 = pgm_read_dword(((uint32_t*)(ptr_lang_table0 + 12)));
  1073. printf_P(_n(" _lt_magic = 0x%08lx %S\n"), _lt_magic, (_lt_magic==0x4bb45aa5)?_n("OK"):_n("NA"));
  1074. printf_P(_n(" _lt_size = 0x%04x (%d)\n"), _lt_size, _lt_size);
  1075. printf_P(_n(" _lt_count = 0x%04x (%d)\n"), _lt_count, _lt_count);
  1076. printf_P(_n(" _lt_chsum = 0x%04x\n"), _lt_chsum);
  1077. printf_P(_n(" _lt_resv0 = 0x%04x\n"), _lt_resv0);
  1078. printf_P(_n(" _lt_resv1 = 0x%08lx\n"), _lt_resv1);
  1079. puts_P(_n("\n"));
  1080. if (eeprom_read_byte((uint8_t*)EEPROM_TEMP_CAL_ACTIVE) == 255) {
  1081. eeprom_write_byte((uint8_t*)EEPROM_TEMP_CAL_ACTIVE, 0);
  1082. temp_cal_active = false;
  1083. } else temp_cal_active = eeprom_read_byte((uint8_t*)EEPROM_TEMP_CAL_ACTIVE);
  1084. if (eeprom_read_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA) == 255) {
  1085. //eeprom_write_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 0);
  1086. eeprom_write_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 1);
  1087. int16_t z_shift = 0;
  1088. for (uint8_t i = 0; i < 5; i++) EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + i * 2, &z_shift);
  1089. eeprom_write_byte((uint8_t*)EEPROM_TEMP_CAL_ACTIVE, 0);
  1090. temp_cal_active = false;
  1091. }
  1092. if (eeprom_read_byte((uint8_t*)EEPROM_UVLO) == 255) {
  1093. eeprom_write_byte((uint8_t*)EEPROM_UVLO, 0);
  1094. }
  1095. if (eeprom_read_byte((uint8_t*)EEPROM_SD_SORT) == 255) {
  1096. eeprom_write_byte((uint8_t*)EEPROM_SD_SORT, 0);
  1097. }
  1098. check_babystep(); //checking if Z babystep is in allowed range
  1099. #ifdef UVLO_SUPPORT
  1100. setup_uvlo_interrupt();
  1101. #endif //UVLO_SUPPORT
  1102. #if !defined(DEBUG_DISABLE_FANCHECK) && defined(FANCHECK) && defined(TACH_1) && TACH_1 >-1
  1103. setup_fan_interrupt();
  1104. #endif //DEBUG_DISABLE_FANCHECK
  1105. #ifdef PAT9125
  1106. #ifndef DEBUG_DISABLE_FSENSORCHECK
  1107. fsensor_setup_interrupt();
  1108. #endif //DEBUG_DISABLE_FSENSORCHECK
  1109. #endif //PAT9125
  1110. for (int i = 0; i<4; i++) EEPROM_read_B(EEPROM_BOWDEN_LENGTH + i * 2, &bowden_length[i]);
  1111. #ifndef DEBUG_DISABLE_STARTMSGS
  1112. KEEPALIVE_STATE(PAUSED_FOR_USER);
  1113. show_fw_version_warnings();
  1114. switch (hw_changed) {
  1115. //if motherboard or printer type was changed inform user as it can indicate flashing wrong firmware version
  1116. //if user confirms with knob, new hw version (printer and/or motherboard) is written to eeprom and message will be not shown next time
  1117. case(0b01):
  1118. lcd_show_fullscreen_message_and_wait_P(_i("Warning: motherboard type changed.")); ////MSG_CHANGED_MOTHERBOARD c=20 r=4
  1119. eeprom_write_word((uint16_t*)EEPROM_BOARD_TYPE, MOTHERBOARD);
  1120. break;
  1121. case(0b10):
  1122. lcd_show_fullscreen_message_and_wait_P(_i("Warning: printer type changed.")); ////MSG_CHANGED_PRINTER c=20 r=4
  1123. eeprom_write_word((uint16_t*)EEPROM_PRINTER_TYPE, PRINTER_TYPE);
  1124. break;
  1125. case(0b11):
  1126. lcd_show_fullscreen_message_and_wait_P(_i("Warning: both printer type and motherboard type changed.")); ////MSG_CHANGED_BOTH c=20 r=4
  1127. eeprom_write_word((uint16_t*)EEPROM_PRINTER_TYPE, PRINTER_TYPE);
  1128. eeprom_write_word((uint16_t*)EEPROM_BOARD_TYPE, MOTHERBOARD);
  1129. break;
  1130. default: break; //no change, show no message
  1131. }
  1132. if (!previous_settings_retrieved) {
  1133. lcd_show_fullscreen_message_and_wait_P(_i("Old settings found. Default PID, Esteps etc. will be set.")); //if EEPROM version or printer type was changed, inform user that default setting were loaded////MSG_DEFAULT_SETTINGS_LOADED c=20 r=4
  1134. erase_eeprom_section(EEPROM_OFFSET, 156); //erase M500 part of eeprom
  1135. }
  1136. if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 1) {
  1137. lcd_wizard(0);
  1138. }
  1139. if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 0) { //dont show calibration status messages if wizard is currently active
  1140. if (calibration_status() == CALIBRATION_STATUS_ASSEMBLED ||
  1141. calibration_status() == CALIBRATION_STATUS_UNKNOWN ||
  1142. calibration_status() == CALIBRATION_STATUS_XYZ_CALIBRATION) {
  1143. // Reset the babystepping values, so the printer will not move the Z axis up when the babystepping is enabled.
  1144. eeprom_update_word((uint16_t*)EEPROM_BABYSTEP_Z, 0);
  1145. // Show the message.
  1146. lcd_show_fullscreen_message_and_wait_P(_T(MSG_FOLLOW_CALIBRATION_FLOW));
  1147. }
  1148. else if (calibration_status() == CALIBRATION_STATUS_LIVE_ADJUST) {
  1149. // Show the message.
  1150. lcd_show_fullscreen_message_and_wait_P(_T(MSG_BABYSTEP_Z_NOT_SET));
  1151. lcd_update_enable(true);
  1152. }
  1153. else if (calibration_status() == CALIBRATION_STATUS_CALIBRATED && temp_cal_active == true && calibration_status_pinda() == false) {
  1154. //lcd_show_fullscreen_message_and_wait_P(_i("Temperature calibration has not been run yet"));////MSG_PINDA_NOT_CALIBRATED c=20 r=4
  1155. lcd_update_enable(true);
  1156. }
  1157. else if (calibration_status() == CALIBRATION_STATUS_Z_CALIBRATION) {
  1158. // Show the message.
  1159. lcd_show_fullscreen_message_and_wait_P(_T(MSG_FOLLOW_CALIBRATION_FLOW));
  1160. }
  1161. }
  1162. #if !defined (DEBUG_DISABLE_FORCE_SELFTEST) && defined (TMC2130)
  1163. if (force_selftest_if_fw_version() && calibration_status() < CALIBRATION_STATUS_ASSEMBLED) {
  1164. lcd_show_fullscreen_message_and_wait_P(_i("Selftest will be run to calibrate accurate sensorless rehoming."));////MSG_FORCE_SELFTEST c=20 r=8
  1165. update_current_firmware_version_to_eeprom();
  1166. lcd_selftest();
  1167. }
  1168. #endif //TMC2130 && !DEBUG_DISABLE_FORCE_SELFTEST
  1169. KEEPALIVE_STATE(IN_PROCESS);
  1170. #endif //DEBUG_DISABLE_STARTMSGS
  1171. lcd_update_enable(true);
  1172. lcd_implementation_clear();
  1173. lcd_update(2);
  1174. // Store the currently running firmware into an eeprom,
  1175. // so the next time the firmware gets updated, it will know from which version it has been updated.
  1176. update_current_firmware_version_to_eeprom();
  1177. #ifdef TMC2130
  1178. tmc2130_home_origin[X_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_HOME_X_ORIGIN);
  1179. tmc2130_home_bsteps[X_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_HOME_X_BSTEPS);
  1180. tmc2130_home_fsteps[X_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_HOME_X_FSTEPS);
  1181. if (tmc2130_home_origin[X_AXIS] == 0xff) tmc2130_home_origin[X_AXIS] = 0;
  1182. if (tmc2130_home_bsteps[X_AXIS] == 0xff) tmc2130_home_bsteps[X_AXIS] = 48;
  1183. if (tmc2130_home_fsteps[X_AXIS] == 0xff) tmc2130_home_fsteps[X_AXIS] = 48;
  1184. tmc2130_home_origin[Y_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_HOME_Y_ORIGIN);
  1185. tmc2130_home_bsteps[Y_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_HOME_Y_BSTEPS);
  1186. tmc2130_home_fsteps[Y_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_HOME_Y_FSTEPS);
  1187. if (tmc2130_home_origin[Y_AXIS] == 0xff) tmc2130_home_origin[Y_AXIS] = 0;
  1188. if (tmc2130_home_bsteps[Y_AXIS] == 0xff) tmc2130_home_bsteps[Y_AXIS] = 48;
  1189. if (tmc2130_home_fsteps[Y_AXIS] == 0xff) tmc2130_home_fsteps[Y_AXIS] = 48;
  1190. tmc2130_home_enabled = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_HOME_ENABLED);
  1191. if (tmc2130_home_enabled == 0xff) tmc2130_home_enabled = 0;
  1192. #endif //TMC2130
  1193. #ifdef UVLO_SUPPORT
  1194. if (eeprom_read_byte((uint8_t*)EEPROM_UVLO) == 1) { //previous print was terminated by UVLO
  1195. /*
  1196. if (lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_RECOVER_PRINT), false)) recover_print();
  1197. else {
  1198. eeprom_update_byte((uint8_t*)EEPROM_UVLO, 0);
  1199. lcd_update_enable(true);
  1200. lcd_update(2);
  1201. lcd_setstatuspgm(_T(WELCOME_MSG));
  1202. }
  1203. */
  1204. manage_heater(); // Update temperatures
  1205. #ifdef DEBUG_UVLO_AUTOMATIC_RECOVER
  1206. MYSERIAL.println("Power panic detected!");
  1207. MYSERIAL.print("Current bed temp:");
  1208. MYSERIAL.println(degBed());
  1209. MYSERIAL.print("Saved bed temp:");
  1210. MYSERIAL.println((float)eeprom_read_byte((uint8_t*)EEPROM_UVLO_TARGET_BED));
  1211. #endif
  1212. if ( degBed() > ( (float)eeprom_read_byte((uint8_t*)EEPROM_UVLO_TARGET_BED) - AUTOMATIC_UVLO_BED_TEMP_OFFSET) ){
  1213. #ifdef DEBUG_UVLO_AUTOMATIC_RECOVER
  1214. MYSERIAL.println("Automatic recovery!");
  1215. #endif
  1216. recover_print(1);
  1217. }
  1218. else{
  1219. #ifdef DEBUG_UVLO_AUTOMATIC_RECOVER
  1220. MYSERIAL.println("Normal recovery!");
  1221. #endif
  1222. if ( lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_RECOVER_PRINT), false) ) recover_print(0);
  1223. else {
  1224. eeprom_update_byte((uint8_t*)EEPROM_UVLO, 0);
  1225. lcd_update_enable(true);
  1226. lcd_update(2);
  1227. lcd_setstatuspgm(_T(WELCOME_MSG));
  1228. }
  1229. }
  1230. }
  1231. #endif //UVLO_SUPPORT
  1232. KEEPALIVE_STATE(NOT_BUSY);
  1233. #ifdef WATCHDOG
  1234. wdt_enable(WDTO_4S);
  1235. #endif //WATCHDOG
  1236. }
  1237. #ifdef PAT9125
  1238. void fsensor_init() {
  1239. int pat9125 = pat9125_init();
  1240. printf_P(PSTR("PAT9125_init:%d\n"), pat9125);
  1241. uint8_t fsensor = eeprom_read_byte((uint8_t*)EEPROM_FSENSOR);
  1242. if (!pat9125)
  1243. {
  1244. fsensor = 0; //disable sensor
  1245. fsensor_not_responding = true;
  1246. }
  1247. else {
  1248. fsensor_not_responding = false;
  1249. }
  1250. puts_P(PSTR("FSensor "));
  1251. if (fsensor)
  1252. {
  1253. puts_P(PSTR("ENABLED\n"));
  1254. fsensor_enable();
  1255. }
  1256. else
  1257. {
  1258. puts_P(PSTR("DISABLED\n"));
  1259. fsensor_disable();
  1260. }
  1261. #ifdef DEBUG_DISABLE_FSENSORCHECK
  1262. filament_autoload_enabled = false;
  1263. fsensor_disable();
  1264. #endif //DEBUG_DISABLE_FSENSORCHECK
  1265. }
  1266. #endif //PAT9125
  1267. void trace();
  1268. #define CHUNK_SIZE 64 // bytes
  1269. #define SAFETY_MARGIN 1
  1270. char chunk[CHUNK_SIZE+SAFETY_MARGIN];
  1271. int chunkHead = 0;
  1272. int serial_read_stream() {
  1273. setTargetHotend(0, 0);
  1274. setTargetBed(0);
  1275. lcd_implementation_clear();
  1276. lcd_printPGM(PSTR(" Upload in progress"));
  1277. // first wait for how many bytes we will receive
  1278. uint32_t bytesToReceive;
  1279. // receive the four bytes
  1280. char bytesToReceiveBuffer[4];
  1281. for (int i=0; i<4; i++) {
  1282. int data;
  1283. while ((data = MYSERIAL.read()) == -1) {};
  1284. bytesToReceiveBuffer[i] = data;
  1285. }
  1286. // make it a uint32
  1287. memcpy(&bytesToReceive, &bytesToReceiveBuffer, 4);
  1288. // we're ready, notify the sender
  1289. MYSERIAL.write('+');
  1290. // lock in the routine
  1291. uint32_t receivedBytes = 0;
  1292. while (prusa_sd_card_upload) {
  1293. int i;
  1294. for (i=0; i<CHUNK_SIZE; i++) {
  1295. int data;
  1296. // check if we're not done
  1297. if (receivedBytes == bytesToReceive) {
  1298. break;
  1299. }
  1300. // read the next byte
  1301. while ((data = MYSERIAL.read()) == -1) {};
  1302. receivedBytes++;
  1303. // save it to the chunk
  1304. chunk[i] = data;
  1305. }
  1306. // write the chunk to SD
  1307. card.write_command_no_newline(&chunk[0]);
  1308. // notify the sender we're ready for more data
  1309. MYSERIAL.write('+');
  1310. // for safety
  1311. manage_heater();
  1312. // check if we're done
  1313. if(receivedBytes == bytesToReceive) {
  1314. trace(); // beep
  1315. card.closefile();
  1316. prusa_sd_card_upload = false;
  1317. SERIAL_PROTOCOLLNRPGM(MSG_FILE_SAVED);
  1318. return 0;
  1319. }
  1320. }
  1321. }
  1322. #ifdef HOST_KEEPALIVE_FEATURE
  1323. /**
  1324. * Output a "busy" message at regular intervals
  1325. * while the machine is not accepting commands.
  1326. */
  1327. void host_keepalive() {
  1328. if (farm_mode) return;
  1329. long ms = millis();
  1330. if (host_keepalive_interval && busy_state != NOT_BUSY) {
  1331. if ((ms - prev_busy_signal_ms) < (long)(1000L * host_keepalive_interval)) return;
  1332. switch (busy_state) {
  1333. case IN_HANDLER:
  1334. case IN_PROCESS:
  1335. SERIAL_ECHO_START;
  1336. SERIAL_ECHOLNPGM("busy: processing");
  1337. break;
  1338. case PAUSED_FOR_USER:
  1339. SERIAL_ECHO_START;
  1340. SERIAL_ECHOLNPGM("busy: paused for user");
  1341. break;
  1342. case PAUSED_FOR_INPUT:
  1343. SERIAL_ECHO_START;
  1344. SERIAL_ECHOLNPGM("busy: paused for input");
  1345. break;
  1346. default:
  1347. break;
  1348. }
  1349. }
  1350. prev_busy_signal_ms = ms;
  1351. }
  1352. #endif
  1353. // The loop() function is called in an endless loop by the Arduino framework from the default main() routine.
  1354. // Before loop(), the setup() function is called by the main() routine.
  1355. void loop()
  1356. {
  1357. KEEPALIVE_STATE(NOT_BUSY);
  1358. bool stack_integrity = true;
  1359. if ((usb_printing_counter > 0) && ((millis()-_usb_timer) > 1000))
  1360. {
  1361. is_usb_printing = true;
  1362. usb_printing_counter--;
  1363. _usb_timer = millis();
  1364. }
  1365. if (usb_printing_counter == 0)
  1366. {
  1367. is_usb_printing = false;
  1368. }
  1369. if (prusa_sd_card_upload)
  1370. {
  1371. //we read byte-by byte
  1372. serial_read_stream();
  1373. } else
  1374. {
  1375. get_command();
  1376. #ifdef SDSUPPORT
  1377. card.checkautostart(false);
  1378. #endif
  1379. if(buflen)
  1380. {
  1381. cmdbuffer_front_already_processed = false;
  1382. #ifdef SDSUPPORT
  1383. if(card.saving)
  1384. {
  1385. // Saving a G-code file onto an SD-card is in progress.
  1386. // Saving starts with M28, saving until M29 is seen.
  1387. if(strstr_P(CMDBUFFER_CURRENT_STRING, PSTR("M29")) == NULL) {
  1388. card.write_command(CMDBUFFER_CURRENT_STRING);
  1389. if(card.logging)
  1390. process_commands();
  1391. else
  1392. SERIAL_PROTOCOLLNRPGM(_T(MSG_OK));
  1393. } else {
  1394. card.closefile();
  1395. SERIAL_PROTOCOLLNRPGM(MSG_FILE_SAVED);
  1396. }
  1397. } else {
  1398. process_commands();
  1399. }
  1400. #else
  1401. process_commands();
  1402. #endif //SDSUPPORT
  1403. if (! cmdbuffer_front_already_processed && buflen)
  1404. {
  1405. // ptr points to the start of the block currently being processed.
  1406. // The first character in the block is the block type.
  1407. char *ptr = cmdbuffer + bufindr;
  1408. if (*ptr == CMDBUFFER_CURRENT_TYPE_SDCARD) {
  1409. // To support power panic, move the lenght of the command on the SD card to a planner buffer.
  1410. union {
  1411. struct {
  1412. char lo;
  1413. char hi;
  1414. } lohi;
  1415. uint16_t value;
  1416. } sdlen;
  1417. sdlen.value = 0;
  1418. {
  1419. // This block locks the interrupts globally for 3.25 us,
  1420. // which corresponds to a maximum repeat frequency of 307.69 kHz.
  1421. // This blocking is safe in the context of a 10kHz stepper driver interrupt
  1422. // or a 115200 Bd serial line receive interrupt, which will not trigger faster than 12kHz.
  1423. cli();
  1424. // Reset the command to something, which will be ignored by the power panic routine,
  1425. // so this buffer length will not be counted twice.
  1426. *ptr ++ = CMDBUFFER_CURRENT_TYPE_TO_BE_REMOVED;
  1427. // Extract the current buffer length.
  1428. sdlen.lohi.lo = *ptr ++;
  1429. sdlen.lohi.hi = *ptr;
  1430. // and pass it to the planner queue.
  1431. planner_add_sd_length(sdlen.value);
  1432. sei();
  1433. }
  1434. }
  1435. // Now it is safe to release the already processed command block. If interrupted by the power panic now,
  1436. // this block's SD card length will not be counted twice as its command type has been replaced
  1437. // by CMDBUFFER_CURRENT_TYPE_TO_BE_REMOVED.
  1438. cmdqueue_pop_front();
  1439. }
  1440. host_keepalive();
  1441. }
  1442. }
  1443. //check heater every n milliseconds
  1444. manage_heater();
  1445. isPrintPaused ? manage_inactivity(true) : manage_inactivity(false);
  1446. checkHitEndstops();
  1447. lcd_update();
  1448. #ifdef PAT9125
  1449. fsensor_update();
  1450. #endif //PAT9125
  1451. #ifdef TMC2130
  1452. tmc2130_check_overtemp();
  1453. if (tmc2130_sg_crash)
  1454. {
  1455. uint8_t crash = tmc2130_sg_crash;
  1456. tmc2130_sg_crash = 0;
  1457. // crashdet_stop_and_save_print();
  1458. switch (crash)
  1459. {
  1460. case 1: enquecommand_P((PSTR("CRASH_DETECTEDX"))); break;
  1461. case 2: enquecommand_P((PSTR("CRASH_DETECTEDY"))); break;
  1462. case 3: enquecommand_P((PSTR("CRASH_DETECTEDXY"))); break;
  1463. }
  1464. }
  1465. #endif //TMC2130
  1466. }
  1467. #define DEFINE_PGM_READ_ANY(type, reader) \
  1468. static inline type pgm_read_any(const type *p) \
  1469. { return pgm_read_##reader##_near(p); }
  1470. DEFINE_PGM_READ_ANY(float, float);
  1471. DEFINE_PGM_READ_ANY(signed char, byte);
  1472. #define XYZ_CONSTS_FROM_CONFIG(type, array, CONFIG) \
  1473. static const PROGMEM type array##_P[3] = \
  1474. { X_##CONFIG, Y_##CONFIG, Z_##CONFIG }; \
  1475. static inline type array(int axis) \
  1476. { return pgm_read_any(&array##_P[axis]); } \
  1477. type array##_ext(int axis) \
  1478. { return pgm_read_any(&array##_P[axis]); }
  1479. XYZ_CONSTS_FROM_CONFIG(float, base_min_pos, MIN_POS);
  1480. XYZ_CONSTS_FROM_CONFIG(float, base_max_pos, MAX_POS);
  1481. XYZ_CONSTS_FROM_CONFIG(float, base_home_pos, HOME_POS);
  1482. XYZ_CONSTS_FROM_CONFIG(float, max_length, MAX_LENGTH);
  1483. XYZ_CONSTS_FROM_CONFIG(float, home_retract_mm, HOME_RETRACT_MM);
  1484. XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR);
  1485. static void axis_is_at_home(int axis) {
  1486. current_position[axis] = base_home_pos(axis) + add_homing[axis];
  1487. min_pos[axis] = base_min_pos(axis) + add_homing[axis];
  1488. max_pos[axis] = base_max_pos(axis) + add_homing[axis];
  1489. }
  1490. inline void set_current_to_destination() { memcpy(current_position, destination, sizeof(current_position)); }
  1491. inline void set_destination_to_current() { memcpy(destination, current_position, sizeof(destination)); }
  1492. static void setup_for_endstop_move(bool enable_endstops_now = true) {
  1493. saved_feedrate = feedrate;
  1494. saved_feedmultiply = feedmultiply;
  1495. feedmultiply = 100;
  1496. previous_millis_cmd = millis();
  1497. enable_endstops(enable_endstops_now);
  1498. }
  1499. static void clean_up_after_endstop_move() {
  1500. #ifdef ENDSTOPS_ONLY_FOR_HOMING
  1501. enable_endstops(false);
  1502. #endif
  1503. feedrate = saved_feedrate;
  1504. feedmultiply = saved_feedmultiply;
  1505. previous_millis_cmd = millis();
  1506. }
  1507. #ifdef ENABLE_AUTO_BED_LEVELING
  1508. #ifdef AUTO_BED_LEVELING_GRID
  1509. static void set_bed_level_equation_lsq(double *plane_equation_coefficients)
  1510. {
  1511. vector_3 planeNormal = vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1);
  1512. planeNormal.debug("planeNormal");
  1513. plan_bed_level_matrix = matrix_3x3::create_look_at(planeNormal);
  1514. //bedLevel.debug("bedLevel");
  1515. //plan_bed_level_matrix.debug("bed level before");
  1516. //vector_3 uncorrected_position = plan_get_position_mm();
  1517. //uncorrected_position.debug("position before");
  1518. vector_3 corrected_position = plan_get_position();
  1519. // corrected_position.debug("position after");
  1520. current_position[X_AXIS] = corrected_position.x;
  1521. current_position[Y_AXIS] = corrected_position.y;
  1522. current_position[Z_AXIS] = corrected_position.z;
  1523. // put the bed at 0 so we don't go below it.
  1524. current_position[Z_AXIS] = zprobe_zoffset; // in the lsq we reach here after raising the extruder due to the loop structure
  1525. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1526. }
  1527. #else // not AUTO_BED_LEVELING_GRID
  1528. static void set_bed_level_equation_3pts(float z_at_pt_1, float z_at_pt_2, float z_at_pt_3) {
  1529. plan_bed_level_matrix.set_to_identity();
  1530. vector_3 pt1 = vector_3(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, z_at_pt_1);
  1531. vector_3 pt2 = vector_3(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, z_at_pt_2);
  1532. vector_3 pt3 = vector_3(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, z_at_pt_3);
  1533. vector_3 from_2_to_1 = (pt1 - pt2).get_normal();
  1534. vector_3 from_2_to_3 = (pt3 - pt2).get_normal();
  1535. vector_3 planeNormal = vector_3::cross(from_2_to_1, from_2_to_3).get_normal();
  1536. planeNormal = vector_3(planeNormal.x, planeNormal.y, abs(planeNormal.z));
  1537. plan_bed_level_matrix = matrix_3x3::create_look_at(planeNormal);
  1538. vector_3 corrected_position = plan_get_position();
  1539. current_position[X_AXIS] = corrected_position.x;
  1540. current_position[Y_AXIS] = corrected_position.y;
  1541. current_position[Z_AXIS] = corrected_position.z;
  1542. // put the bed at 0 so we don't go below it.
  1543. current_position[Z_AXIS] = zprobe_zoffset;
  1544. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1545. }
  1546. #endif // AUTO_BED_LEVELING_GRID
  1547. static void run_z_probe() {
  1548. plan_bed_level_matrix.set_to_identity();
  1549. feedrate = homing_feedrate[Z_AXIS];
  1550. // move down until you find the bed
  1551. float zPosition = -10;
  1552. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate/60, active_extruder);
  1553. st_synchronize();
  1554. // we have to let the planner know where we are right now as it is not where we said to go.
  1555. zPosition = st_get_position_mm(Z_AXIS);
  1556. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS]);
  1557. // move up the retract distance
  1558. zPosition += home_retract_mm(Z_AXIS);
  1559. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate/60, active_extruder);
  1560. st_synchronize();
  1561. // move back down slowly to find bed
  1562. feedrate = homing_feedrate[Z_AXIS]/4;
  1563. zPosition -= home_retract_mm(Z_AXIS) * 2;
  1564. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate/60, active_extruder);
  1565. st_synchronize();
  1566. current_position[Z_AXIS] = st_get_position_mm(Z_AXIS);
  1567. // make sure the planner knows where we are as it may be a bit different than we last said to move to
  1568. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1569. }
  1570. static void do_blocking_move_to(float x, float y, float z) {
  1571. float oldFeedRate = feedrate;
  1572. feedrate = homing_feedrate[Z_AXIS];
  1573. current_position[Z_AXIS] = z;
  1574. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate/60, active_extruder);
  1575. st_synchronize();
  1576. feedrate = XY_TRAVEL_SPEED;
  1577. current_position[X_AXIS] = x;
  1578. current_position[Y_AXIS] = y;
  1579. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate/60, active_extruder);
  1580. st_synchronize();
  1581. feedrate = oldFeedRate;
  1582. }
  1583. static void do_blocking_move_relative(float offset_x, float offset_y, float offset_z) {
  1584. do_blocking_move_to(current_position[X_AXIS] + offset_x, current_position[Y_AXIS] + offset_y, current_position[Z_AXIS] + offset_z);
  1585. }
  1586. /// Probe bed height at position (x,y), returns the measured z value
  1587. static float probe_pt(float x, float y, float z_before) {
  1588. // move to right place
  1589. do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z_before);
  1590. do_blocking_move_to(x - X_PROBE_OFFSET_FROM_EXTRUDER, y - Y_PROBE_OFFSET_FROM_EXTRUDER, current_position[Z_AXIS]);
  1591. run_z_probe();
  1592. float measured_z = current_position[Z_AXIS];
  1593. SERIAL_PROTOCOLRPGM(_T(MSG_BED));
  1594. SERIAL_PROTOCOLPGM(" x: ");
  1595. SERIAL_PROTOCOL(x);
  1596. SERIAL_PROTOCOLPGM(" y: ");
  1597. SERIAL_PROTOCOL(y);
  1598. SERIAL_PROTOCOLPGM(" z: ");
  1599. SERIAL_PROTOCOL(measured_z);
  1600. SERIAL_PROTOCOLPGM("\n");
  1601. return measured_z;
  1602. }
  1603. #endif // #ifdef ENABLE_AUTO_BED_LEVELING
  1604. #ifdef LIN_ADVANCE
  1605. /**
  1606. * M900: Set and/or Get advance K factor and WH/D ratio
  1607. *
  1608. * K<factor> Set advance K factor
  1609. * R<ratio> Set ratio directly (overrides WH/D)
  1610. * W<width> H<height> D<diam> Set ratio from WH/D
  1611. */
  1612. inline void gcode_M900() {
  1613. st_synchronize();
  1614. const float newK = code_seen('K') ? code_value_float() : -1;
  1615. if (newK >= 0) extruder_advance_k = newK;
  1616. float newR = code_seen('R') ? code_value_float() : -1;
  1617. if (newR < 0) {
  1618. const float newD = code_seen('D') ? code_value_float() : -1,
  1619. newW = code_seen('W') ? code_value_float() : -1,
  1620. newH = code_seen('H') ? code_value_float() : -1;
  1621. if (newD >= 0 && newW >= 0 && newH >= 0)
  1622. newR = newD ? (newW * newH) / (sq(newD * 0.5) * M_PI) : 0;
  1623. }
  1624. if (newR >= 0) advance_ed_ratio = newR;
  1625. SERIAL_ECHO_START;
  1626. SERIAL_ECHOPGM("Advance K=");
  1627. SERIAL_ECHOLN(extruder_advance_k);
  1628. SERIAL_ECHOPGM(" E/D=");
  1629. const float ratio = advance_ed_ratio;
  1630. if (ratio) SERIAL_ECHOLN(ratio); else SERIAL_ECHOLNPGM("Auto");
  1631. }
  1632. #endif // LIN_ADVANCE
  1633. bool check_commands() {
  1634. bool end_command_found = false;
  1635. while (buflen)
  1636. {
  1637. if ((code_seen("M84")) || (code_seen("M 84"))) end_command_found = true;
  1638. if (!cmdbuffer_front_already_processed)
  1639. cmdqueue_pop_front();
  1640. cmdbuffer_front_already_processed = false;
  1641. }
  1642. return end_command_found;
  1643. }
  1644. #ifdef TMC2130
  1645. bool calibrate_z_auto()
  1646. {
  1647. //lcd_display_message_fullscreen_P(_T(MSG_CALIBRATE_Z_AUTO));
  1648. lcd_implementation_clear();
  1649. lcd_print_at_PGM(0,1, _T(MSG_CALIBRATE_Z_AUTO));
  1650. bool endstops_enabled = enable_endstops(true);
  1651. int axis_up_dir = -home_dir(Z_AXIS);
  1652. tmc2130_home_enter(Z_AXIS_MASK);
  1653. current_position[Z_AXIS] = 0;
  1654. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1655. set_destination_to_current();
  1656. destination[Z_AXIS] += (1.1 * max_length(Z_AXIS) * axis_up_dir);
  1657. feedrate = homing_feedrate[Z_AXIS];
  1658. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1659. st_synchronize();
  1660. // current_position[axis] = 0;
  1661. // plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1662. tmc2130_home_exit();
  1663. enable_endstops(false);
  1664. current_position[Z_AXIS] = 0;
  1665. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1666. set_destination_to_current();
  1667. destination[Z_AXIS] += 10 * axis_up_dir; //10mm up
  1668. feedrate = homing_feedrate[Z_AXIS] / 2;
  1669. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1670. st_synchronize();
  1671. enable_endstops(endstops_enabled);
  1672. current_position[Z_AXIS] = Z_MAX_POS+2.0;
  1673. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1674. return true;
  1675. }
  1676. #endif //TMC2130
  1677. void homeaxis(int axis, uint8_t cnt, uint8_t* pstep)
  1678. {
  1679. bool endstops_enabled = enable_endstops(true); //RP: endstops should be allways enabled durring homing
  1680. #define HOMEAXIS_DO(LETTER) \
  1681. ((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1))
  1682. if ((axis==X_AXIS)?HOMEAXIS_DO(X):(axis==Y_AXIS)?HOMEAXIS_DO(Y):0)
  1683. {
  1684. int axis_home_dir = home_dir(axis);
  1685. feedrate = homing_feedrate[axis];
  1686. #ifdef TMC2130
  1687. tmc2130_home_enter(X_AXIS_MASK << axis);
  1688. #endif //TMC2130
  1689. // Move right a bit, so that the print head does not touch the left end position,
  1690. // and the following left movement has a chance to achieve the required velocity
  1691. // for the stall guard to work.
  1692. current_position[axis] = 0;
  1693. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1694. set_destination_to_current();
  1695. // destination[axis] = 11.f;
  1696. destination[axis] = 3.f;
  1697. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1698. st_synchronize();
  1699. // Move left away from the possible collision with the collision detection disabled.
  1700. endstops_hit_on_purpose();
  1701. enable_endstops(false);
  1702. current_position[axis] = 0;
  1703. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1704. destination[axis] = - 1.;
  1705. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1706. st_synchronize();
  1707. // Now continue to move up to the left end stop with the collision detection enabled.
  1708. enable_endstops(true);
  1709. destination[axis] = - 1.1 * max_length(axis);
  1710. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1711. st_synchronize();
  1712. for (uint8_t i = 0; i < cnt; i++)
  1713. {
  1714. // Move right from the collision to a known distance from the left end stop with the collision detection disabled.
  1715. endstops_hit_on_purpose();
  1716. enable_endstops(false);
  1717. current_position[axis] = 0;
  1718. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1719. destination[axis] = 10.f;
  1720. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1721. st_synchronize();
  1722. endstops_hit_on_purpose();
  1723. // Now move left up to the collision, this time with a repeatable velocity.
  1724. enable_endstops(true);
  1725. destination[axis] = - 11.f;
  1726. #ifdef TMC2130
  1727. feedrate = homing_feedrate[axis];
  1728. #else //TMC2130
  1729. feedrate = homing_feedrate[axis] / 2;
  1730. #endif //TMC2130
  1731. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1732. st_synchronize();
  1733. #ifdef TMC2130
  1734. uint16_t mscnt = tmc2130_rd_MSCNT(axis);
  1735. if (pstep) pstep[i] = mscnt >> 4;
  1736. printf_P(PSTR("%3d step=%2d mscnt=%4d\n"), i, mscnt >> 4, mscnt);
  1737. #endif //TMC2130
  1738. }
  1739. endstops_hit_on_purpose();
  1740. enable_endstops(false);
  1741. #ifdef TMC2130
  1742. uint8_t orig = tmc2130_home_origin[axis];
  1743. uint8_t back = tmc2130_home_bsteps[axis];
  1744. if (tmc2130_home_enabled && (orig <= 63))
  1745. {
  1746. tmc2130_goto_step(axis, orig, 2, 1000, tmc2130_get_res(axis));
  1747. if (back > 0)
  1748. tmc2130_do_steps(axis, back, 1, 1000);
  1749. }
  1750. else
  1751. tmc2130_do_steps(axis, 8, 2, 1000);
  1752. tmc2130_home_exit();
  1753. #endif //TMC2130
  1754. axis_is_at_home(axis);
  1755. axis_known_position[axis] = true;
  1756. // Move from minimum
  1757. #ifdef TMC2130
  1758. float dist = 0.01f * tmc2130_home_fsteps[axis];
  1759. #else //TMC2130
  1760. float dist = 0.01f * 64;
  1761. #endif //TMC2130
  1762. current_position[axis] -= dist;
  1763. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1764. current_position[axis] += dist;
  1765. destination[axis] = current_position[axis];
  1766. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], 0.5f*feedrate/60, active_extruder);
  1767. st_synchronize();
  1768. feedrate = 0.0;
  1769. }
  1770. else if ((axis==Z_AXIS)?HOMEAXIS_DO(Z):0)
  1771. {
  1772. int axis_home_dir = home_dir(axis);
  1773. current_position[axis] = 0;
  1774. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1775. destination[axis] = 1.5 * max_length(axis) * axis_home_dir;
  1776. feedrate = homing_feedrate[axis];
  1777. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1778. st_synchronize();
  1779. #ifdef TMC2130
  1780. if ((tmc2130_mode == TMC2130_MODE_NORMAL) && (READ(Z_TMC2130_DIAG) != 0)) return; //Z crash
  1781. #endif //TMC2130
  1782. current_position[axis] = 0;
  1783. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1784. destination[axis] = -home_retract_mm(axis) * axis_home_dir;
  1785. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1786. st_synchronize();
  1787. destination[axis] = 2*home_retract_mm(axis) * axis_home_dir;
  1788. feedrate = homing_feedrate[axis]/2 ;
  1789. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1790. st_synchronize();
  1791. #ifdef TMC2130
  1792. if ((tmc2130_mode == TMC2130_MODE_NORMAL) && (READ(Z_TMC2130_DIAG) != 0)) return; //Z crash
  1793. #endif //TMC2130
  1794. axis_is_at_home(axis);
  1795. destination[axis] = current_position[axis];
  1796. feedrate = 0.0;
  1797. endstops_hit_on_purpose();
  1798. axis_known_position[axis] = true;
  1799. }
  1800. enable_endstops(endstops_enabled);
  1801. }
  1802. /**/
  1803. void home_xy()
  1804. {
  1805. set_destination_to_current();
  1806. homeaxis(X_AXIS);
  1807. homeaxis(Y_AXIS);
  1808. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1809. endstops_hit_on_purpose();
  1810. }
  1811. void refresh_cmd_timeout(void)
  1812. {
  1813. previous_millis_cmd = millis();
  1814. }
  1815. #ifdef FWRETRACT
  1816. void retract(bool retracting, bool swapretract = false) {
  1817. if(retracting && !retracted[active_extruder]) {
  1818. destination[X_AXIS]=current_position[X_AXIS];
  1819. destination[Y_AXIS]=current_position[Y_AXIS];
  1820. destination[Z_AXIS]=current_position[Z_AXIS];
  1821. destination[E_AXIS]=current_position[E_AXIS];
  1822. current_position[E_AXIS]+=(swapretract?retract_length_swap:retract_length)*float(extrudemultiply)*0.01f;
  1823. plan_set_e_position(current_position[E_AXIS]);
  1824. float oldFeedrate = feedrate;
  1825. feedrate=retract_feedrate*60;
  1826. retracted[active_extruder]=true;
  1827. prepare_move();
  1828. current_position[Z_AXIS]-=retract_zlift;
  1829. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1830. prepare_move();
  1831. feedrate = oldFeedrate;
  1832. } else if(!retracting && retracted[active_extruder]) {
  1833. destination[X_AXIS]=current_position[X_AXIS];
  1834. destination[Y_AXIS]=current_position[Y_AXIS];
  1835. destination[Z_AXIS]=current_position[Z_AXIS];
  1836. destination[E_AXIS]=current_position[E_AXIS];
  1837. current_position[Z_AXIS]+=retract_zlift;
  1838. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1839. current_position[E_AXIS]-=(swapretract?(retract_length_swap+retract_recover_length_swap):(retract_length+retract_recover_length))*float(extrudemultiply)*0.01f;
  1840. plan_set_e_position(current_position[E_AXIS]);
  1841. float oldFeedrate = feedrate;
  1842. feedrate=retract_recover_feedrate*60;
  1843. retracted[active_extruder]=false;
  1844. prepare_move();
  1845. feedrate = oldFeedrate;
  1846. }
  1847. } //retract
  1848. #endif //FWRETRACT
  1849. void trace() {
  1850. tone(BEEPER, 440);
  1851. delay(25);
  1852. noTone(BEEPER);
  1853. delay(20);
  1854. }
  1855. /*
  1856. void ramming() {
  1857. // float tmp[4] = DEFAULT_MAX_FEEDRATE;
  1858. if (current_temperature[0] < 230) {
  1859. //PLA
  1860. max_feedrate[E_AXIS] = 50;
  1861. //current_position[E_AXIS] -= 8;
  1862. //plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2100 / 60, active_extruder);
  1863. //current_position[E_AXIS] += 8;
  1864. //plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2100 / 60, active_extruder);
  1865. current_position[E_AXIS] += 5.4;
  1866. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2800 / 60, active_extruder);
  1867. current_position[E_AXIS] += 3.2;
  1868. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  1869. current_position[E_AXIS] += 3;
  1870. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3400 / 60, active_extruder);
  1871. st_synchronize();
  1872. max_feedrate[E_AXIS] = 80;
  1873. current_position[E_AXIS] -= 82;
  1874. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 9500 / 60, active_extruder);
  1875. max_feedrate[E_AXIS] = 50;//tmp[E_AXIS];
  1876. current_position[E_AXIS] -= 20;
  1877. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 1200 / 60, active_extruder);
  1878. current_position[E_AXIS] += 5;
  1879. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 400 / 60, active_extruder);
  1880. current_position[E_AXIS] += 5;
  1881. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600 / 60, active_extruder);
  1882. current_position[E_AXIS] -= 10;
  1883. st_synchronize();
  1884. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600 / 60, active_extruder);
  1885. current_position[E_AXIS] += 10;
  1886. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600 / 60, active_extruder);
  1887. current_position[E_AXIS] -= 10;
  1888. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 800 / 60, active_extruder);
  1889. current_position[E_AXIS] += 10;
  1890. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 800 / 60, active_extruder);
  1891. current_position[E_AXIS] -= 10;
  1892. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 800 / 60, active_extruder);
  1893. st_synchronize();
  1894. }
  1895. else {
  1896. //ABS
  1897. max_feedrate[E_AXIS] = 50;
  1898. //current_position[E_AXIS] -= 8;
  1899. //plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2100 / 60, active_extruder);
  1900. //current_position[E_AXIS] += 8;
  1901. //plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2100 / 60, active_extruder);
  1902. current_position[E_AXIS] += 3.1;
  1903. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2000 / 60, active_extruder);
  1904. current_position[E_AXIS] += 3.1;
  1905. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2500 / 60, active_extruder);
  1906. current_position[E_AXIS] += 4;
  1907. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  1908. st_synchronize();
  1909. //current_position[X_AXIS] += 23; //delay
  1910. //plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600/60, active_extruder); //delay
  1911. //current_position[X_AXIS] -= 23; //delay
  1912. //plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600/60, active_extruder); //delay
  1913. delay(4700);
  1914. max_feedrate[E_AXIS] = 80;
  1915. current_position[E_AXIS] -= 92;
  1916. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 9900 / 60, active_extruder);
  1917. max_feedrate[E_AXIS] = 50;//tmp[E_AXIS];
  1918. current_position[E_AXIS] -= 5;
  1919. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 800 / 60, active_extruder);
  1920. current_position[E_AXIS] += 5;
  1921. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 400 / 60, active_extruder);
  1922. current_position[E_AXIS] -= 5;
  1923. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600 / 60, active_extruder);
  1924. st_synchronize();
  1925. current_position[E_AXIS] += 5;
  1926. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600 / 60, active_extruder);
  1927. current_position[E_AXIS] -= 5;
  1928. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600 / 60, active_extruder);
  1929. current_position[E_AXIS] += 5;
  1930. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600 / 60, active_extruder);
  1931. current_position[E_AXIS] -= 5;
  1932. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600 / 60, active_extruder);
  1933. st_synchronize();
  1934. }
  1935. }
  1936. */
  1937. #ifdef TMC2130
  1938. void force_high_power_mode(bool start_high_power_section) {
  1939. uint8_t silent;
  1940. silent = eeprom_read_byte((uint8_t*)EEPROM_SILENT);
  1941. if (silent == 1) {
  1942. //we are in silent mode, set to normal mode to enable crash detection
  1943. // Wait for the planner queue to drain and for the stepper timer routine to reach an idle state.
  1944. st_synchronize();
  1945. cli();
  1946. tmc2130_mode = (start_high_power_section == true) ? TMC2130_MODE_NORMAL : TMC2130_MODE_SILENT;
  1947. tmc2130_init();
  1948. // We may have missed a stepper timer interrupt due to the time spent in the tmc2130_init() routine.
  1949. // Be safe than sorry, reset the stepper timer before re-enabling interrupts.
  1950. st_reset_timer();
  1951. sei();
  1952. }
  1953. }
  1954. #endif //TMC2130
  1955. bool gcode_M45(bool onlyZ, int8_t verbosity_level)
  1956. {
  1957. bool final_result = false;
  1958. #ifdef TMC2130
  1959. FORCE_HIGH_POWER_START;
  1960. #endif // TMC2130
  1961. // Only Z calibration?
  1962. if (!onlyZ)
  1963. {
  1964. setTargetBed(0);
  1965. setTargetHotend(0, 0);
  1966. setTargetHotend(0, 1);
  1967. setTargetHotend(0, 2);
  1968. adjust_bed_reset(); //reset bed level correction
  1969. }
  1970. // Disable the default update procedure of the display. We will do a modal dialog.
  1971. lcd_update_enable(false);
  1972. // Let the planner use the uncorrected coordinates.
  1973. mbl.reset();
  1974. // Reset world2machine_rotation_and_skew and world2machine_shift, therefore
  1975. // the planner will not perform any adjustments in the XY plane.
  1976. // Wait for the motors to stop and update the current position with the absolute values.
  1977. world2machine_revert_to_uncorrected();
  1978. // Reset the baby step value applied without moving the axes.
  1979. babystep_reset();
  1980. // Mark all axes as in a need for homing.
  1981. memset(axis_known_position, 0, sizeof(axis_known_position));
  1982. // Home in the XY plane.
  1983. //set_destination_to_current();
  1984. setup_for_endstop_move();
  1985. lcd_display_message_fullscreen_P(_T(MSG_AUTO_HOME));
  1986. home_xy();
  1987. enable_endstops(false);
  1988. current_position[X_AXIS] += 5;
  1989. current_position[Y_AXIS] += 5;
  1990. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 40, active_extruder);
  1991. st_synchronize();
  1992. // Let the user move the Z axes up to the end stoppers.
  1993. #ifdef TMC2130
  1994. if (calibrate_z_auto())
  1995. {
  1996. #else //TMC2130
  1997. if (lcd_calibrate_z_end_stop_manual(onlyZ))
  1998. {
  1999. #endif //TMC2130
  2000. refresh_cmd_timeout();
  2001. #ifndef STEEL_SHEET
  2002. if (((degHotend(0) > MAX_HOTEND_TEMP_CALIBRATION) || (degBed() > MAX_BED_TEMP_CALIBRATION)) && (!onlyZ))
  2003. {
  2004. lcd_wait_for_cool_down();
  2005. }
  2006. #endif //STEEL_SHEET
  2007. if(!onlyZ)
  2008. {
  2009. KEEPALIVE_STATE(PAUSED_FOR_USER);
  2010. #ifdef STEEL_SHEET
  2011. bool result = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_STEEL_SHEET_CHECK), false, false);
  2012. if(result) lcd_show_fullscreen_message_and_wait_P(_T(MSG_REMOVE_STEEL_SHEET));
  2013. #endif //STEEL_SHEET
  2014. lcd_show_fullscreen_message_and_wait_P(_T(MSG_CONFIRM_NOZZLE_CLEAN));
  2015. lcd_show_fullscreen_message_and_wait_P(_T(MSG_PAPER));
  2016. KEEPALIVE_STATE(IN_HANDLER);
  2017. lcd_display_message_fullscreen_P(_T(MSG_FIND_BED_OFFSET_AND_SKEW_LINE1));
  2018. lcd_implementation_print_at(0, 2, 1);
  2019. lcd_printPGM(_T(MSG_FIND_BED_OFFSET_AND_SKEW_LINE2));
  2020. }
  2021. // Move the print head close to the bed.
  2022. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  2023. bool endstops_enabled = enable_endstops(true);
  2024. #ifdef TMC2130
  2025. tmc2130_home_enter(Z_AXIS_MASK);
  2026. #endif //TMC2130
  2027. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 40, active_extruder);
  2028. st_synchronize();
  2029. #ifdef TMC2130
  2030. tmc2130_home_exit();
  2031. #endif //TMC2130
  2032. enable_endstops(endstops_enabled);
  2033. if (st_get_position_mm(Z_AXIS) == MESH_HOME_Z_SEARCH)
  2034. {
  2035. int8_t verbosity_level = 0;
  2036. if (code_seen('V'))
  2037. {
  2038. // Just 'V' without a number counts as V1.
  2039. char c = strchr_pointer[1];
  2040. verbosity_level = (c == ' ' || c == '\t' || c == 0) ? 1 : code_value_short();
  2041. }
  2042. if (onlyZ)
  2043. {
  2044. clean_up_after_endstop_move();
  2045. // Z only calibration.
  2046. // Load the machine correction matrix
  2047. world2machine_initialize();
  2048. // and correct the current_position to match the transformed coordinate system.
  2049. world2machine_update_current();
  2050. //FIXME
  2051. bool result = sample_mesh_and_store_reference();
  2052. if (result)
  2053. {
  2054. if (calibration_status() == CALIBRATION_STATUS_Z_CALIBRATION)
  2055. // Shipped, the nozzle height has been set already. The user can start printing now.
  2056. calibration_status_store(CALIBRATION_STATUS_CALIBRATED);
  2057. final_result = true;
  2058. // babystep_apply();
  2059. }
  2060. }
  2061. else
  2062. {
  2063. // Reset the baby step value and the baby step applied flag.
  2064. calibration_status_store(CALIBRATION_STATUS_XYZ_CALIBRATION);
  2065. eeprom_update_word((uint16_t*)EEPROM_BABYSTEP_Z, 0);
  2066. // Complete XYZ calibration.
  2067. uint8_t point_too_far_mask = 0;
  2068. BedSkewOffsetDetectionResultType result = find_bed_offset_and_skew(verbosity_level, point_too_far_mask);
  2069. clean_up_after_endstop_move();
  2070. // Print head up.
  2071. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  2072. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 40, active_extruder);
  2073. st_synchronize();
  2074. //#ifndef NEW_XYZCAL
  2075. if (result >= 0)
  2076. {
  2077. #ifdef HEATBED_V2
  2078. sample_z();
  2079. #else //HEATBED_V2
  2080. point_too_far_mask = 0;
  2081. // Second half: The fine adjustment.
  2082. // Let the planner use the uncorrected coordinates.
  2083. mbl.reset();
  2084. world2machine_reset();
  2085. // Home in the XY plane.
  2086. setup_for_endstop_move();
  2087. home_xy();
  2088. result = improve_bed_offset_and_skew(1, verbosity_level, point_too_far_mask);
  2089. clean_up_after_endstop_move();
  2090. // Print head up.
  2091. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  2092. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 40, active_extruder);
  2093. st_synchronize();
  2094. // if (result >= 0) babystep_apply();
  2095. #endif //HEATBED_V2
  2096. }
  2097. //#endif //NEW_XYZCAL
  2098. lcd_update_enable(true);
  2099. lcd_update(2);
  2100. lcd_bed_calibration_show_result(result, point_too_far_mask);
  2101. if (result >= 0)
  2102. {
  2103. // Calibration valid, the machine should be able to print. Advise the user to run the V2Calibration.gcode.
  2104. calibration_status_store(CALIBRATION_STATUS_LIVE_ADJUST);
  2105. if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) != 1) lcd_show_fullscreen_message_and_wait_P(_T(MSG_BABYSTEP_Z_NOT_SET));
  2106. final_result = true;
  2107. }
  2108. }
  2109. #ifdef TMC2130
  2110. tmc2130_home_exit();
  2111. #endif
  2112. }
  2113. else
  2114. {
  2115. lcd_show_fullscreen_message_and_wait_P(PSTR("Calibration failed! Check the axes and run again."));
  2116. final_result = false;
  2117. }
  2118. }
  2119. else
  2120. {
  2121. // Timeouted.
  2122. }
  2123. lcd_update_enable(true);
  2124. #ifdef TMC2130
  2125. FORCE_HIGH_POWER_END;
  2126. #endif // TMC2130
  2127. return final_result;
  2128. }
  2129. void gcode_M114()
  2130. {
  2131. SERIAL_PROTOCOLPGM("X:");
  2132. SERIAL_PROTOCOL(current_position[X_AXIS]);
  2133. SERIAL_PROTOCOLPGM(" Y:");
  2134. SERIAL_PROTOCOL(current_position[Y_AXIS]);
  2135. SERIAL_PROTOCOLPGM(" Z:");
  2136. SERIAL_PROTOCOL(current_position[Z_AXIS]);
  2137. SERIAL_PROTOCOLPGM(" E:");
  2138. SERIAL_PROTOCOL(current_position[E_AXIS]);
  2139. SERIAL_PROTOCOLRPGM(_n(" Count X: "));////MSG_COUNT_X c=0 r=0
  2140. SERIAL_PROTOCOL(float(st_get_position(X_AXIS)) / axis_steps_per_unit[X_AXIS]);
  2141. SERIAL_PROTOCOLPGM(" Y:");
  2142. SERIAL_PROTOCOL(float(st_get_position(Y_AXIS)) / axis_steps_per_unit[Y_AXIS]);
  2143. SERIAL_PROTOCOLPGM(" Z:");
  2144. SERIAL_PROTOCOL(float(st_get_position(Z_AXIS)) / axis_steps_per_unit[Z_AXIS]);
  2145. SERIAL_PROTOCOLPGM(" E:");
  2146. SERIAL_PROTOCOL(float(st_get_position(E_AXIS)) / axis_steps_per_unit[E_AXIS]);
  2147. SERIAL_PROTOCOLLN("");
  2148. }
  2149. void gcode_M701()
  2150. {
  2151. #ifdef SNMM
  2152. extr_adj(snmm_extruder);//loads current extruder
  2153. #else
  2154. enable_z();
  2155. custom_message = true;
  2156. custom_message_type = 2;
  2157. lcd_setstatuspgm(_T(MSG_LOADING_FILAMENT));
  2158. current_position[E_AXIS] += 70;
  2159. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 400 / 60, active_extruder); //fast sequence
  2160. current_position[E_AXIS] += 25;
  2161. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 100 / 60, active_extruder); //slow sequence
  2162. st_synchronize();
  2163. tone(BEEPER, 500);
  2164. delay_keep_alive(50);
  2165. noTone(BEEPER);
  2166. if (!farm_mode && loading_flag) {
  2167. bool clean = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_FILAMENT_CLEAN), false, true);
  2168. while (!clean) {
  2169. lcd_update_enable(true);
  2170. lcd_update(2);
  2171. current_position[E_AXIS] += 25;
  2172. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 100 / 60, active_extruder); //slow sequence
  2173. st_synchronize();
  2174. clean = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_FILAMENT_CLEAN), false, true);
  2175. }
  2176. }
  2177. lcd_update_enable(true);
  2178. lcd_update(2);
  2179. lcd_setstatuspgm(_T(WELCOME_MSG));
  2180. disable_z();
  2181. loading_flag = false;
  2182. custom_message = false;
  2183. custom_message_type = 0;
  2184. #endif
  2185. }
  2186. /**
  2187. * @brief Get serial number from 32U2 processor
  2188. *
  2189. * Typical format of S/N is:CZPX0917X003XC13518
  2190. *
  2191. * Command operates only in farm mode, if not in farm mode, "Not in farm mode." is written to MYSERIAL.
  2192. *
  2193. * Send command ;S to serial port 0 to retrieve serial number stored in 32U2 processor,
  2194. * reply is transmitted to serial port 1 character by character.
  2195. * Operation takes typically 23 ms. If the retransmit is not finished until 100 ms,
  2196. * it is interrupted, so less, or no characters are retransmitted, only newline character is send
  2197. * in any case.
  2198. */
  2199. static void gcode_PRUSA_SN()
  2200. {
  2201. if (farm_mode) {
  2202. selectedSerialPort = 0;
  2203. MSerial.write(";S");
  2204. int numbersRead = 0;
  2205. Timer timeout;
  2206. timeout.start();
  2207. while (numbersRead < 19) {
  2208. while (MSerial.available() > 0) {
  2209. uint8_t serial_char = MSerial.read();
  2210. selectedSerialPort = 1;
  2211. MSerial.write(serial_char);
  2212. numbersRead++;
  2213. selectedSerialPort = 0;
  2214. }
  2215. if (timeout.expired(100)) break;
  2216. }
  2217. selectedSerialPort = 1;
  2218. MSerial.write('\n');
  2219. #if 0
  2220. for (int b = 0; b < 3; b++) {
  2221. tone(BEEPER, 110);
  2222. delay(50);
  2223. noTone(BEEPER);
  2224. delay(50);
  2225. }
  2226. #endif
  2227. } else {
  2228. MYSERIAL.println("Not in farm mode.");
  2229. }
  2230. }
  2231. void process_commands()
  2232. {
  2233. if (!buflen) return; //empty command
  2234. #ifdef FILAMENT_RUNOUT_SUPPORT
  2235. SET_INPUT(FR_SENS);
  2236. #endif
  2237. #ifdef CMDBUFFER_DEBUG
  2238. SERIAL_ECHOPGM("Processing a GCODE command: ");
  2239. SERIAL_ECHO(cmdbuffer+bufindr+CMDHDRSIZE);
  2240. SERIAL_ECHOLNPGM("");
  2241. SERIAL_ECHOPGM("In cmdqueue: ");
  2242. SERIAL_ECHO(buflen);
  2243. SERIAL_ECHOLNPGM("");
  2244. #endif /* CMDBUFFER_DEBUG */
  2245. unsigned long codenum; //throw away variable
  2246. char *starpos = NULL;
  2247. #ifdef ENABLE_AUTO_BED_LEVELING
  2248. float x_tmp, y_tmp, z_tmp, real_z;
  2249. #endif
  2250. // PRUSA GCODES
  2251. KEEPALIVE_STATE(IN_HANDLER);
  2252. #ifdef SNMM
  2253. float tmp_motor[3] = DEFAULT_PWM_MOTOR_CURRENT;
  2254. float tmp_motor_loud[3] = DEFAULT_PWM_MOTOR_CURRENT_LOUD;
  2255. int8_t SilentMode;
  2256. #endif
  2257. if (code_seen("M117")) { //moved to highest priority place to be able to to print strings which includes "G", "PRUSA" and "^"
  2258. starpos = (strchr(strchr_pointer + 5, '*'));
  2259. if (starpos != NULL)
  2260. *(starpos) = '\0';
  2261. lcd_setstatus(strchr_pointer + 5);
  2262. }
  2263. #ifdef TMC2130
  2264. else if (strncmp_P(CMDBUFFER_CURRENT_STRING, PSTR("CRASH_"), 6) == 0)
  2265. {
  2266. if(code_seen("CRASH_DETECTED"))
  2267. {
  2268. uint8_t mask = 0;
  2269. if (code_seen("X")) mask |= X_AXIS_MASK;
  2270. if (code_seen("Y")) mask |= Y_AXIS_MASK;
  2271. crashdet_detected(mask);
  2272. }
  2273. else if(code_seen("CRASH_RECOVER"))
  2274. crashdet_recover();
  2275. else if(code_seen("CRASH_CANCEL"))
  2276. crashdet_cancel();
  2277. }
  2278. else if (strncmp_P(CMDBUFFER_CURRENT_STRING, PSTR("TMC_"), 4) == 0)
  2279. {
  2280. if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_WAVE_E"), 10) == 0)
  2281. {
  2282. uint8_t fac = (uint8_t)strtol(CMDBUFFER_CURRENT_STRING + 14, NULL, 10);
  2283. tmc2130_set_wave(E_AXIS, 247, fac);
  2284. }
  2285. else if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_STEP_E"), 10) == 0)
  2286. {
  2287. uint8_t step = (uint8_t)strtol(CMDBUFFER_CURRENT_STRING + 14, NULL, 10);
  2288. uint16_t res = tmc2130_get_res(E_AXIS);
  2289. tmc2130_goto_step(E_AXIS, step & (4*res - 1), 2, 1000, res);
  2290. }
  2291. }
  2292. #endif //TMC2130
  2293. else if(code_seen("PRUSA")){
  2294. if (code_seen("Ping")) { //PRUSA Ping
  2295. if (farm_mode) {
  2296. PingTime = millis();
  2297. //MYSERIAL.print(farm_no); MYSERIAL.println(": OK");
  2298. }
  2299. }
  2300. else if (code_seen("PRN")) {
  2301. MYSERIAL.println(status_number);
  2302. }else if (code_seen("FAN")) {
  2303. MYSERIAL.print("E0:");
  2304. MYSERIAL.print(60*fan_speed[0]);
  2305. MYSERIAL.println(" RPM");
  2306. MYSERIAL.print("PRN0:");
  2307. MYSERIAL.print(60*fan_speed[1]);
  2308. MYSERIAL.println(" RPM");
  2309. }else if (code_seen("fn")) {
  2310. if (farm_mode) {
  2311. MYSERIAL.println(farm_no);
  2312. }
  2313. else {
  2314. MYSERIAL.println("Not in farm mode.");
  2315. }
  2316. }
  2317. else if (code_seen("thx")) {
  2318. no_response = false;
  2319. }else if (code_seen("fv")) {
  2320. // get file version
  2321. #ifdef SDSUPPORT
  2322. card.openFile(strchr_pointer + 3,true);
  2323. while (true) {
  2324. uint16_t readByte = card.get();
  2325. MYSERIAL.write(readByte);
  2326. if (readByte=='\n') {
  2327. break;
  2328. }
  2329. }
  2330. card.closefile();
  2331. #endif // SDSUPPORT
  2332. } else if (code_seen("M28")) {
  2333. trace();
  2334. prusa_sd_card_upload = true;
  2335. card.openFile(strchr_pointer+4,false);
  2336. } else if (code_seen("SN")) {
  2337. gcode_PRUSA_SN();
  2338. } else if(code_seen("Fir")){
  2339. SERIAL_PROTOCOLLN(FW_VERSION);
  2340. } else if(code_seen("Rev")){
  2341. SERIAL_PROTOCOLLN(FILAMENT_SIZE "-" ELECTRONICS "-" NOZZLE_TYPE );
  2342. } else if(code_seen("Lang")) {
  2343. lcd_force_language_selection();
  2344. } else if(code_seen("Lz")) {
  2345. EEPROM_save_B(EEPROM_BABYSTEP_Z,0);
  2346. } else if (code_seen("SERIAL LOW")) {
  2347. MYSERIAL.println("SERIAL LOW");
  2348. MYSERIAL.begin(BAUDRATE);
  2349. return;
  2350. } else if (code_seen("SERIAL HIGH")) {
  2351. MYSERIAL.println("SERIAL HIGH");
  2352. MYSERIAL.begin(1152000);
  2353. return;
  2354. } else if(code_seen("Beat")) {
  2355. // Kick farm link timer
  2356. kicktime = millis();
  2357. } else if(code_seen("FR")) {
  2358. // Factory full reset
  2359. factory_reset(0,true);
  2360. }
  2361. //else if (code_seen('Cal')) {
  2362. // lcd_calibration();
  2363. // }
  2364. }
  2365. else if (code_seen('^')) {
  2366. // nothing, this is a version line
  2367. } else if(code_seen('G'))
  2368. {
  2369. switch((int)code_value())
  2370. {
  2371. case 0: // G0 -> G1
  2372. case 1: // G1
  2373. if(Stopped == false) {
  2374. #ifdef FILAMENT_RUNOUT_SUPPORT
  2375. if(READ(FR_SENS)){
  2376. feedmultiplyBckp=feedmultiply;
  2377. float target[4];
  2378. float lastpos[4];
  2379. target[X_AXIS]=current_position[X_AXIS];
  2380. target[Y_AXIS]=current_position[Y_AXIS];
  2381. target[Z_AXIS]=current_position[Z_AXIS];
  2382. target[E_AXIS]=current_position[E_AXIS];
  2383. lastpos[X_AXIS]=current_position[X_AXIS];
  2384. lastpos[Y_AXIS]=current_position[Y_AXIS];
  2385. lastpos[Z_AXIS]=current_position[Z_AXIS];
  2386. lastpos[E_AXIS]=current_position[E_AXIS];
  2387. //retract by E
  2388. target[E_AXIS]+= FILAMENTCHANGE_FIRSTRETRACT ;
  2389. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 400, active_extruder);
  2390. target[Z_AXIS]+= FILAMENTCHANGE_ZADD ;
  2391. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 300, active_extruder);
  2392. target[X_AXIS]= FILAMENTCHANGE_XPOS ;
  2393. target[Y_AXIS]= FILAMENTCHANGE_YPOS ;
  2394. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 70, active_extruder);
  2395. target[E_AXIS]+= FILAMENTCHANGE_FINALRETRACT ;
  2396. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 20, active_extruder);
  2397. //finish moves
  2398. st_synchronize();
  2399. //disable extruder steppers so filament can be removed
  2400. disable_e0();
  2401. disable_e1();
  2402. disable_e2();
  2403. delay(100);
  2404. //LCD_ALERTMESSAGEPGM(_T(MSG_FILAMENTCHANGE));
  2405. uint8_t cnt=0;
  2406. int counterBeep = 0;
  2407. lcd_wait_interact();
  2408. while(!lcd_clicked()){
  2409. cnt++;
  2410. manage_heater();
  2411. manage_inactivity(true);
  2412. //lcd_update();
  2413. if(cnt==0)
  2414. {
  2415. #if BEEPER > 0
  2416. if (counterBeep== 500){
  2417. counterBeep = 0;
  2418. }
  2419. SET_OUTPUT(BEEPER);
  2420. if (counterBeep== 0){
  2421. WRITE(BEEPER,HIGH);
  2422. }
  2423. if (counterBeep== 20){
  2424. WRITE(BEEPER,LOW);
  2425. }
  2426. counterBeep++;
  2427. #else
  2428. #if !defined(LCD_FEEDBACK_FREQUENCY_HZ) || !defined(LCD_FEEDBACK_FREQUENCY_DURATION_MS)
  2429. lcd_buzz(1000/6,100);
  2430. #else
  2431. lcd_buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS,LCD_FEEDBACK_FREQUENCY_HZ);
  2432. #endif
  2433. #endif
  2434. }
  2435. }
  2436. WRITE(BEEPER,LOW);
  2437. target[E_AXIS]+= FILAMENTCHANGE_FIRSTFEED ;
  2438. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 20, active_extruder);
  2439. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  2440. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  2441. lcd_change_fil_state = 0;
  2442. lcd_loading_filament();
  2443. while ((lcd_change_fil_state == 0)||(lcd_change_fil_state != 1)){
  2444. lcd_change_fil_state = 0;
  2445. lcd_alright();
  2446. switch(lcd_change_fil_state){
  2447. case 2:
  2448. target[E_AXIS]+= FILAMENTCHANGE_FIRSTFEED ;
  2449. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 20, active_extruder);
  2450. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  2451. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  2452. lcd_loading_filament();
  2453. break;
  2454. case 3:
  2455. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  2456. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  2457. lcd_loading_color();
  2458. break;
  2459. default:
  2460. lcd_change_success();
  2461. break;
  2462. }
  2463. }
  2464. target[E_AXIS]+= 5;
  2465. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  2466. target[E_AXIS]+= FILAMENTCHANGE_FIRSTRETRACT;
  2467. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 400, active_extruder);
  2468. //current_position[E_AXIS]=target[E_AXIS]; //the long retract of L is compensated by manual filament feeding
  2469. //plan_set_e_position(current_position[E_AXIS]);
  2470. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 70, active_extruder); //should do nothing
  2471. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], target[Z_AXIS], target[E_AXIS], 70, active_extruder); //move xy back
  2472. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], target[E_AXIS], 200, active_extruder); //move z back
  2473. target[E_AXIS]= target[E_AXIS] - FILAMENTCHANGE_FIRSTRETRACT;
  2474. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], target[E_AXIS], 5, active_extruder); //final untretract
  2475. plan_set_e_position(lastpos[E_AXIS]);
  2476. feedmultiply=feedmultiplyBckp;
  2477. char cmd[9];
  2478. sprintf_P(cmd, PSTR("M220 S%i"), feedmultiplyBckp);
  2479. enquecommand(cmd);
  2480. }
  2481. #endif
  2482. get_coordinates(); // For X Y Z E F
  2483. if (total_filament_used > ((current_position[E_AXIS] - destination[E_AXIS]) * 100)) { //protection against total_filament_used overflow
  2484. total_filament_used = total_filament_used + ((destination[E_AXIS] - current_position[E_AXIS]) * 100);
  2485. }
  2486. #ifdef FWRETRACT
  2487. if(autoretract_enabled)
  2488. if( !(code_seen('X') || code_seen('Y') || code_seen('Z')) && code_seen('E')) {
  2489. float echange=destination[E_AXIS]-current_position[E_AXIS];
  2490. if((echange<-MIN_RETRACT && !retracted) || (echange>MIN_RETRACT && retracted)) { //move appears to be an attempt to retract or recover
  2491. current_position[E_AXIS] = destination[E_AXIS]; //hide the slicer-generated retract/recover from calculations
  2492. plan_set_e_position(current_position[E_AXIS]); //AND from the planner
  2493. retract(!retracted);
  2494. return;
  2495. }
  2496. }
  2497. #endif //FWRETRACT
  2498. prepare_move();
  2499. //ClearToSend();
  2500. }
  2501. break;
  2502. case 2: // G2 - CW ARC
  2503. if(Stopped == false) {
  2504. get_arc_coordinates();
  2505. prepare_arc_move(true);
  2506. }
  2507. break;
  2508. case 3: // G3 - CCW ARC
  2509. if(Stopped == false) {
  2510. get_arc_coordinates();
  2511. prepare_arc_move(false);
  2512. }
  2513. break;
  2514. case 4: // G4 dwell
  2515. codenum = 0;
  2516. if(code_seen('P')) codenum = code_value(); // milliseconds to wait
  2517. if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait
  2518. if(codenum != 0) LCD_MESSAGERPGM(_i("Sleep..."));////MSG_DWELL c=0 r=0
  2519. st_synchronize();
  2520. codenum += millis(); // keep track of when we started waiting
  2521. previous_millis_cmd = millis();
  2522. while(millis() < codenum) {
  2523. manage_heater();
  2524. manage_inactivity();
  2525. lcd_update();
  2526. }
  2527. break;
  2528. #ifdef FWRETRACT
  2529. case 10: // G10 retract
  2530. #if EXTRUDERS > 1
  2531. retracted_swap[active_extruder]=(code_seen('S') && code_value_long() == 1); // checks for swap retract argument
  2532. retract(true,retracted_swap[active_extruder]);
  2533. #else
  2534. retract(true);
  2535. #endif
  2536. break;
  2537. case 11: // G11 retract_recover
  2538. #if EXTRUDERS > 1
  2539. retract(false,retracted_swap[active_extruder]);
  2540. #else
  2541. retract(false);
  2542. #endif
  2543. break;
  2544. #endif //FWRETRACT
  2545. case 28: //G28 Home all Axis one at a time
  2546. {
  2547. st_synchronize();
  2548. #if 0
  2549. SERIAL_ECHOPGM("G28, initial "); print_world_coordinates();
  2550. SERIAL_ECHOPGM("G28, initial "); print_physical_coordinates();
  2551. #endif
  2552. // Flag for the display update routine and to disable the print cancelation during homing.
  2553. homing_flag = true;
  2554. // Which axes should be homed?
  2555. bool home_x = code_seen(axis_codes[X_AXIS]);
  2556. bool home_y = code_seen(axis_codes[Y_AXIS]);
  2557. bool home_z = code_seen(axis_codes[Z_AXIS]);
  2558. // calibrate?
  2559. bool calib = code_seen('C');
  2560. // Either all X,Y,Z codes are present, or none of them.
  2561. bool home_all_axes = home_x == home_y && home_x == home_z;
  2562. if (home_all_axes)
  2563. // No X/Y/Z code provided means to home all axes.
  2564. home_x = home_y = home_z = true;
  2565. #ifdef ENABLE_AUTO_BED_LEVELING
  2566. plan_bed_level_matrix.set_to_identity(); //Reset the plane ("erase" all leveling data)
  2567. #endif //ENABLE_AUTO_BED_LEVELING
  2568. // Reset world2machine_rotation_and_skew and world2machine_shift, therefore
  2569. // the planner will not perform any adjustments in the XY plane.
  2570. // Wait for the motors to stop and update the current position with the absolute values.
  2571. world2machine_revert_to_uncorrected();
  2572. // For mesh bed leveling deactivate the matrix temporarily.
  2573. // It is necessary to disable the bed leveling for the X and Y homing moves, so that the move is performed
  2574. // in a single axis only.
  2575. // In case of re-homing the X or Y axes only, the mesh bed leveling is restored after G28.
  2576. #ifdef MESH_BED_LEVELING
  2577. uint8_t mbl_was_active = mbl.active;
  2578. mbl.active = 0;
  2579. current_position[Z_AXIS] = st_get_position_mm(Z_AXIS);
  2580. #endif
  2581. // Reset baby stepping to zero, if the babystepping has already been loaded before. The babystepsTodo value will be
  2582. // consumed during the first movements following this statement.
  2583. if (home_z)
  2584. babystep_undo();
  2585. saved_feedrate = feedrate;
  2586. saved_feedmultiply = feedmultiply;
  2587. feedmultiply = 100;
  2588. previous_millis_cmd = millis();
  2589. enable_endstops(true);
  2590. memcpy(destination, current_position, sizeof(destination));
  2591. feedrate = 0.0;
  2592. #if Z_HOME_DIR > 0 // If homing away from BED do Z first
  2593. if(home_z)
  2594. homeaxis(Z_AXIS);
  2595. #endif
  2596. #ifdef QUICK_HOME
  2597. // In the quick mode, if both x and y are to be homed, a diagonal move will be performed initially.
  2598. if(home_x && home_y) //first diagonal move
  2599. {
  2600. current_position[X_AXIS] = 0;current_position[Y_AXIS] = 0;
  2601. int x_axis_home_dir = home_dir(X_AXIS);
  2602. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  2603. destination[X_AXIS] = 1.5 * max_length(X_AXIS) * x_axis_home_dir;destination[Y_AXIS] = 1.5 * max_length(Y_AXIS) * home_dir(Y_AXIS);
  2604. feedrate = homing_feedrate[X_AXIS];
  2605. if(homing_feedrate[Y_AXIS]<feedrate)
  2606. feedrate = homing_feedrate[Y_AXIS];
  2607. if (max_length(X_AXIS) > max_length(Y_AXIS)) {
  2608. feedrate *= sqrt(pow(max_length(Y_AXIS) / max_length(X_AXIS), 2) + 1);
  2609. } else {
  2610. feedrate *= sqrt(pow(max_length(X_AXIS) / max_length(Y_AXIS), 2) + 1);
  2611. }
  2612. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  2613. st_synchronize();
  2614. axis_is_at_home(X_AXIS);
  2615. axis_is_at_home(Y_AXIS);
  2616. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  2617. destination[X_AXIS] = current_position[X_AXIS];
  2618. destination[Y_AXIS] = current_position[Y_AXIS];
  2619. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  2620. feedrate = 0.0;
  2621. st_synchronize();
  2622. endstops_hit_on_purpose();
  2623. current_position[X_AXIS] = destination[X_AXIS];
  2624. current_position[Y_AXIS] = destination[Y_AXIS];
  2625. current_position[Z_AXIS] = destination[Z_AXIS];
  2626. }
  2627. #endif /* QUICK_HOME */
  2628. #ifdef TMC2130
  2629. if(home_x)
  2630. {
  2631. if (!calib)
  2632. homeaxis(X_AXIS);
  2633. else
  2634. tmc2130_home_calibrate(X_AXIS);
  2635. }
  2636. if(home_y)
  2637. {
  2638. if (!calib)
  2639. homeaxis(Y_AXIS);
  2640. else
  2641. tmc2130_home_calibrate(Y_AXIS);
  2642. }
  2643. #endif //TMC2130
  2644. if(code_seen(axis_codes[X_AXIS]) && code_value_long() != 0)
  2645. current_position[X_AXIS]=code_value()+add_homing[X_AXIS];
  2646. if(code_seen(axis_codes[Y_AXIS]) && code_value_long() != 0)
  2647. current_position[Y_AXIS]=code_value()+add_homing[Y_AXIS];
  2648. #if Z_HOME_DIR < 0 // If homing towards BED do Z last
  2649. #ifndef Z_SAFE_HOMING
  2650. if(home_z) {
  2651. #if defined (Z_RAISE_BEFORE_HOMING) && (Z_RAISE_BEFORE_HOMING > 0)
  2652. destination[Z_AXIS] = Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS) * (-1); // Set destination away from bed
  2653. feedrate = max_feedrate[Z_AXIS];
  2654. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
  2655. st_synchronize();
  2656. #endif // defined (Z_RAISE_BEFORE_HOMING) && (Z_RAISE_BEFORE_HOMING > 0)
  2657. #if (defined(MESH_BED_LEVELING) && !defined(MK1BP)) // If Mesh bed leveling, moxve X&Y to safe position for home
  2658. if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] ))
  2659. {
  2660. homeaxis(X_AXIS);
  2661. homeaxis(Y_AXIS);
  2662. }
  2663. // 1st mesh bed leveling measurement point, corrected.
  2664. world2machine_initialize();
  2665. world2machine(pgm_read_float(bed_ref_points_4), pgm_read_float(bed_ref_points_4+1), destination[X_AXIS], destination[Y_AXIS]);
  2666. world2machine_reset();
  2667. if (destination[Y_AXIS] < Y_MIN_POS)
  2668. destination[Y_AXIS] = Y_MIN_POS;
  2669. destination[Z_AXIS] = MESH_HOME_Z_SEARCH; // Set destination away from bed
  2670. feedrate = homing_feedrate[Z_AXIS]/10;
  2671. current_position[Z_AXIS] = 0;
  2672. enable_endstops(false);
  2673. #ifdef DEBUG_BUILD
  2674. SERIAL_ECHOLNPGM("plan_set_position()");
  2675. MYSERIAL.println(current_position[X_AXIS]);MYSERIAL.println(current_position[Y_AXIS]);
  2676. MYSERIAL.println(current_position[Z_AXIS]);MYSERIAL.println(current_position[E_AXIS]);
  2677. #endif
  2678. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  2679. #ifdef DEBUG_BUILD
  2680. SERIAL_ECHOLNPGM("plan_buffer_line()");
  2681. MYSERIAL.println(destination[X_AXIS]);MYSERIAL.println(destination[Y_AXIS]);
  2682. MYSERIAL.println(destination[Z_AXIS]);MYSERIAL.println(destination[E_AXIS]);
  2683. MYSERIAL.println(feedrate);MYSERIAL.println(active_extruder);
  2684. #endif
  2685. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
  2686. st_synchronize();
  2687. current_position[X_AXIS] = destination[X_AXIS];
  2688. current_position[Y_AXIS] = destination[Y_AXIS];
  2689. enable_endstops(true);
  2690. endstops_hit_on_purpose();
  2691. homeaxis(Z_AXIS);
  2692. #else // MESH_BED_LEVELING
  2693. homeaxis(Z_AXIS);
  2694. #endif // MESH_BED_LEVELING
  2695. }
  2696. #else // defined(Z_SAFE_HOMING): Z Safe mode activated.
  2697. if(home_all_axes) {
  2698. destination[X_AXIS] = round(Z_SAFE_HOMING_X_POINT - X_PROBE_OFFSET_FROM_EXTRUDER);
  2699. destination[Y_AXIS] = round(Z_SAFE_HOMING_Y_POINT - Y_PROBE_OFFSET_FROM_EXTRUDER);
  2700. destination[Z_AXIS] = Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS) * (-1); // Set destination away from bed
  2701. feedrate = XY_TRAVEL_SPEED/60;
  2702. current_position[Z_AXIS] = 0;
  2703. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  2704. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
  2705. st_synchronize();
  2706. current_position[X_AXIS] = destination[X_AXIS];
  2707. current_position[Y_AXIS] = destination[Y_AXIS];
  2708. homeaxis(Z_AXIS);
  2709. }
  2710. // Let's see if X and Y are homed and probe is inside bed area.
  2711. if(home_z) {
  2712. if ( (axis_known_position[X_AXIS]) && (axis_known_position[Y_AXIS]) \
  2713. && (current_position[X_AXIS]+X_PROBE_OFFSET_FROM_EXTRUDER >= X_MIN_POS) \
  2714. && (current_position[X_AXIS]+X_PROBE_OFFSET_FROM_EXTRUDER <= X_MAX_POS) \
  2715. && (current_position[Y_AXIS]+Y_PROBE_OFFSET_FROM_EXTRUDER >= Y_MIN_POS) \
  2716. && (current_position[Y_AXIS]+Y_PROBE_OFFSET_FROM_EXTRUDER <= Y_MAX_POS)) {
  2717. current_position[Z_AXIS] = 0;
  2718. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  2719. destination[Z_AXIS] = Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS) * (-1); // Set destination away from bed
  2720. feedrate = max_feedrate[Z_AXIS];
  2721. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
  2722. st_synchronize();
  2723. homeaxis(Z_AXIS);
  2724. } else if (!((axis_known_position[X_AXIS]) && (axis_known_position[Y_AXIS]))) {
  2725. LCD_MESSAGERPGM(MSG_POSITION_UNKNOWN);
  2726. SERIAL_ECHO_START;
  2727. SERIAL_ECHOLNRPGM(MSG_POSITION_UNKNOWN);
  2728. } else {
  2729. LCD_MESSAGERPGM(MSG_ZPROBE_OUT);
  2730. SERIAL_ECHO_START;
  2731. SERIAL_ECHOLNRPGM(MSG_ZPROBE_OUT);
  2732. }
  2733. }
  2734. #endif // Z_SAFE_HOMING
  2735. #endif // Z_HOME_DIR < 0
  2736. if(code_seen(axis_codes[Z_AXIS]) && code_value_long() != 0)
  2737. current_position[Z_AXIS]=code_value()+add_homing[Z_AXIS];
  2738. #ifdef ENABLE_AUTO_BED_LEVELING
  2739. if(home_z)
  2740. current_position[Z_AXIS] += zprobe_zoffset; //Add Z_Probe offset (the distance is negative)
  2741. #endif
  2742. // Set the planner and stepper routine positions.
  2743. // At this point the mesh bed leveling and world2machine corrections are disabled and current_position
  2744. // contains the machine coordinates.
  2745. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  2746. #ifdef ENDSTOPS_ONLY_FOR_HOMING
  2747. enable_endstops(false);
  2748. #endif
  2749. feedrate = saved_feedrate;
  2750. feedmultiply = saved_feedmultiply;
  2751. previous_millis_cmd = millis();
  2752. endstops_hit_on_purpose();
  2753. #ifndef MESH_BED_LEVELING
  2754. // If MESH_BED_LEVELING is not active, then it is the original Prusa i3.
  2755. // Offer the user to load the baby step value, which has been adjusted at the previous print session.
  2756. if(card.sdprinting && eeprom_read_word((uint16_t *)EEPROM_BABYSTEP_Z))
  2757. lcd_adjust_z();
  2758. #endif
  2759. // Load the machine correction matrix
  2760. world2machine_initialize();
  2761. // and correct the current_position XY axes to match the transformed coordinate system.
  2762. world2machine_update_current();
  2763. #if (defined(MESH_BED_LEVELING) && !defined(MK1BP))
  2764. if (code_seen(axis_codes[X_AXIS]) || code_seen(axis_codes[Y_AXIS]) || code_seen('W') || code_seen(axis_codes[Z_AXIS]))
  2765. {
  2766. if (! home_z && mbl_was_active) {
  2767. // Re-enable the mesh bed leveling if only the X and Y axes were re-homed.
  2768. mbl.active = true;
  2769. // and re-adjust the current logical Z axis with the bed leveling offset applicable at the current XY position.
  2770. current_position[Z_AXIS] -= mbl.get_z(st_get_position_mm(X_AXIS), st_get_position_mm(Y_AXIS));
  2771. }
  2772. }
  2773. else
  2774. {
  2775. st_synchronize();
  2776. homing_flag = false;
  2777. // Push the commands to the front of the message queue in the reverse order!
  2778. // There shall be always enough space reserved for these commands.
  2779. // enquecommand_front_P((PSTR("G80")));
  2780. goto case_G80;
  2781. }
  2782. #endif
  2783. if (farm_mode) { prusa_statistics(20); };
  2784. homing_flag = false;
  2785. #if 0
  2786. SERIAL_ECHOPGM("G28, final "); print_world_coordinates();
  2787. SERIAL_ECHOPGM("G28, final "); print_physical_coordinates();
  2788. SERIAL_ECHOPGM("G28, final "); print_mesh_bed_leveling_table();
  2789. #endif
  2790. break;
  2791. }
  2792. #ifdef ENABLE_AUTO_BED_LEVELING
  2793. case 29: // G29 Detailed Z-Probe, probes the bed at 3 or more points.
  2794. {
  2795. #if Z_MIN_PIN == -1
  2796. #error "You must have a Z_MIN endstop in order to enable Auto Bed Leveling feature! Z_MIN_PIN must point to a valid hardware pin."
  2797. #endif
  2798. // Prevent user from running a G29 without first homing in X and Y
  2799. if (! (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS]) )
  2800. {
  2801. LCD_MESSAGERPGM(MSG_POSITION_UNKNOWN);
  2802. SERIAL_ECHO_START;
  2803. SERIAL_ECHOLNRPGM(MSG_POSITION_UNKNOWN);
  2804. break; // abort G29, since we don't know where we are
  2805. }
  2806. st_synchronize();
  2807. // make sure the bed_level_rotation_matrix is identity or the planner will get it incorectly
  2808. //vector_3 corrected_position = plan_get_position_mm();
  2809. //corrected_position.debug("position before G29");
  2810. plan_bed_level_matrix.set_to_identity();
  2811. vector_3 uncorrected_position = plan_get_position();
  2812. //uncorrected_position.debug("position durring G29");
  2813. current_position[X_AXIS] = uncorrected_position.x;
  2814. current_position[Y_AXIS] = uncorrected_position.y;
  2815. current_position[Z_AXIS] = uncorrected_position.z;
  2816. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  2817. setup_for_endstop_move();
  2818. feedrate = homing_feedrate[Z_AXIS];
  2819. #ifdef AUTO_BED_LEVELING_GRID
  2820. // probe at the points of a lattice grid
  2821. int xGridSpacing = (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION) / (AUTO_BED_LEVELING_GRID_POINTS-1);
  2822. int yGridSpacing = (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION) / (AUTO_BED_LEVELING_GRID_POINTS-1);
  2823. // solve the plane equation ax + by + d = z
  2824. // A is the matrix with rows [x y 1] for all the probed points
  2825. // B is the vector of the Z positions
  2826. // the normal vector to the plane is formed by the coefficients of the plane equation in the standard form, which is Vx*x+Vy*y+Vz*z+d = 0
  2827. // so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z
  2828. // "A" matrix of the linear system of equations
  2829. double eqnAMatrix[AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS*3];
  2830. // "B" vector of Z points
  2831. double eqnBVector[AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS];
  2832. int probePointCounter = 0;
  2833. bool zig = true;
  2834. for (int yProbe=FRONT_PROBE_BED_POSITION; yProbe <= BACK_PROBE_BED_POSITION; yProbe += yGridSpacing)
  2835. {
  2836. int xProbe, xInc;
  2837. if (zig)
  2838. {
  2839. xProbe = LEFT_PROBE_BED_POSITION;
  2840. //xEnd = RIGHT_PROBE_BED_POSITION;
  2841. xInc = xGridSpacing;
  2842. zig = false;
  2843. } else // zag
  2844. {
  2845. xProbe = RIGHT_PROBE_BED_POSITION;
  2846. //xEnd = LEFT_PROBE_BED_POSITION;
  2847. xInc = -xGridSpacing;
  2848. zig = true;
  2849. }
  2850. for (int xCount=0; xCount < AUTO_BED_LEVELING_GRID_POINTS; xCount++)
  2851. {
  2852. float z_before;
  2853. if (probePointCounter == 0)
  2854. {
  2855. // raise before probing
  2856. z_before = Z_RAISE_BEFORE_PROBING;
  2857. } else
  2858. {
  2859. // raise extruder
  2860. z_before = current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS;
  2861. }
  2862. float measured_z = probe_pt(xProbe, yProbe, z_before);
  2863. eqnBVector[probePointCounter] = measured_z;
  2864. eqnAMatrix[probePointCounter + 0*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = xProbe;
  2865. eqnAMatrix[probePointCounter + 1*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = yProbe;
  2866. eqnAMatrix[probePointCounter + 2*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = 1;
  2867. probePointCounter++;
  2868. xProbe += xInc;
  2869. }
  2870. }
  2871. clean_up_after_endstop_move();
  2872. // solve lsq problem
  2873. double *plane_equation_coefficients = qr_solve(AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS, 3, eqnAMatrix, eqnBVector);
  2874. SERIAL_PROTOCOLPGM("Eqn coefficients: a: ");
  2875. SERIAL_PROTOCOL(plane_equation_coefficients[0]);
  2876. SERIAL_PROTOCOLPGM(" b: ");
  2877. SERIAL_PROTOCOL(plane_equation_coefficients[1]);
  2878. SERIAL_PROTOCOLPGM(" d: ");
  2879. SERIAL_PROTOCOLLN(plane_equation_coefficients[2]);
  2880. set_bed_level_equation_lsq(plane_equation_coefficients);
  2881. free(plane_equation_coefficients);
  2882. #else // AUTO_BED_LEVELING_GRID not defined
  2883. // Probe at 3 arbitrary points
  2884. // probe 1
  2885. float z_at_pt_1 = probe_pt(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, Z_RAISE_BEFORE_PROBING);
  2886. // probe 2
  2887. float z_at_pt_2 = probe_pt(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS);
  2888. // probe 3
  2889. float z_at_pt_3 = probe_pt(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS);
  2890. clean_up_after_endstop_move();
  2891. set_bed_level_equation_3pts(z_at_pt_1, z_at_pt_2, z_at_pt_3);
  2892. #endif // AUTO_BED_LEVELING_GRID
  2893. st_synchronize();
  2894. // The following code correct the Z height difference from z-probe position and hotend tip position.
  2895. // The Z height on homing is measured by Z-Probe, but the probe is quite far from the hotend.
  2896. // When the bed is uneven, this height must be corrected.
  2897. real_z = float(st_get_position(Z_AXIS))/axis_steps_per_unit[Z_AXIS]; //get the real Z (since the auto bed leveling is already correcting the plane)
  2898. x_tmp = current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER;
  2899. y_tmp = current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER;
  2900. z_tmp = current_position[Z_AXIS];
  2901. apply_rotation_xyz(plan_bed_level_matrix, x_tmp, y_tmp, z_tmp); //Apply the correction sending the probe offset
  2902. current_position[Z_AXIS] = z_tmp - real_z + current_position[Z_AXIS]; //The difference is added to current position and sent to planner.
  2903. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  2904. }
  2905. break;
  2906. #ifndef Z_PROBE_SLED
  2907. case 30: // G30 Single Z Probe
  2908. {
  2909. st_synchronize();
  2910. // TODO: make sure the bed_level_rotation_matrix is identity or the planner will get set incorectly
  2911. setup_for_endstop_move();
  2912. feedrate = homing_feedrate[Z_AXIS];
  2913. run_z_probe();
  2914. SERIAL_PROTOCOLPGM(_T(MSG_BED));
  2915. SERIAL_PROTOCOLPGM(" X: ");
  2916. SERIAL_PROTOCOL(current_position[X_AXIS]);
  2917. SERIAL_PROTOCOLPGM(" Y: ");
  2918. SERIAL_PROTOCOL(current_position[Y_AXIS]);
  2919. SERIAL_PROTOCOLPGM(" Z: ");
  2920. SERIAL_PROTOCOL(current_position[Z_AXIS]);
  2921. SERIAL_PROTOCOLPGM("\n");
  2922. clean_up_after_endstop_move();
  2923. }
  2924. break;
  2925. #else
  2926. case 31: // dock the sled
  2927. dock_sled(true);
  2928. break;
  2929. case 32: // undock the sled
  2930. dock_sled(false);
  2931. break;
  2932. #endif // Z_PROBE_SLED
  2933. #endif // ENABLE_AUTO_BED_LEVELING
  2934. #ifdef MESH_BED_LEVELING
  2935. case 30: // G30 Single Z Probe
  2936. {
  2937. st_synchronize();
  2938. // TODO: make sure the bed_level_rotation_matrix is identity or the planner will get set incorectly
  2939. setup_for_endstop_move();
  2940. feedrate = homing_feedrate[Z_AXIS];
  2941. find_bed_induction_sensor_point_z(-10.f, 3);
  2942. SERIAL_PROTOCOLRPGM(_T(MSG_BED));
  2943. SERIAL_PROTOCOLPGM(" X: ");
  2944. MYSERIAL.print(current_position[X_AXIS], 5);
  2945. SERIAL_PROTOCOLPGM(" Y: ");
  2946. MYSERIAL.print(current_position[Y_AXIS], 5);
  2947. SERIAL_PROTOCOLPGM(" Z: ");
  2948. MYSERIAL.print(current_position[Z_AXIS], 5);
  2949. SERIAL_PROTOCOLPGM("\n");
  2950. clean_up_after_endstop_move();
  2951. }
  2952. break;
  2953. case 75:
  2954. {
  2955. for (int i = 40; i <= 110; i++) {
  2956. MYSERIAL.print(i);
  2957. MYSERIAL.print(" ");
  2958. MYSERIAL.println(temp_comp_interpolation(i));// / axis_steps_per_unit[Z_AXIS]);
  2959. }
  2960. }
  2961. break;
  2962. case 76: //PINDA probe temperature calibration
  2963. {
  2964. #ifdef PINDA_THERMISTOR
  2965. if (true)
  2966. {
  2967. if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS]))
  2968. {
  2969. // We don't know where we are! HOME!
  2970. // Push the commands to the front of the message queue in the reverse order!
  2971. // There shall be always enough space reserved for these commands.
  2972. repeatcommand_front(); // repeat G76 with all its parameters
  2973. enquecommand_front_P((PSTR("G28 W0")));
  2974. break;
  2975. }
  2976. lcd_show_fullscreen_message_and_wait_P(_i("Stable ambient temperature 21-26C is needed a rigid stand is required."));////MSG_TEMP_CAL_WARNING c=20 r=4
  2977. bool result = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_STEEL_SHEET_CHECK), false, false);
  2978. if (result)
  2979. {
  2980. current_position[Z_AXIS] = 50;
  2981. current_position[Y_AXIS] += 180;
  2982. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  2983. st_synchronize();
  2984. lcd_show_fullscreen_message_and_wait_P(_T(MSG_REMOVE_STEEL_SHEET));
  2985. current_position[Y_AXIS] -= 180;
  2986. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  2987. st_synchronize();
  2988. feedrate = homing_feedrate[Z_AXIS] / 10;
  2989. enable_endstops(true);
  2990. endstops_hit_on_purpose();
  2991. homeaxis(Z_AXIS);
  2992. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  2993. enable_endstops(false);
  2994. }
  2995. if ((current_temperature_pinda > 35) && (farm_mode == false)) {
  2996. //waiting for PIDNA probe to cool down in case that we are not in farm mode
  2997. current_position[Z_AXIS] = 100;
  2998. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  2999. if (lcd_wait_for_pinda(35) == false) { //waiting for PINDA probe to cool, if this takes more then time expected, temp. cal. fails
  3000. lcd_temp_cal_show_result(false);
  3001. break;
  3002. }
  3003. }
  3004. lcd_update_enable(true);
  3005. KEEPALIVE_STATE(NOT_BUSY); //no need to print busy messages as we print current temperatures periodicaly
  3006. SERIAL_ECHOLNPGM("PINDA probe calibration start");
  3007. float zero_z;
  3008. int z_shift = 0; //unit: steps
  3009. float start_temp = 5 * (int)(current_temperature_pinda / 5);
  3010. if (start_temp < 35) start_temp = 35;
  3011. if (start_temp < current_temperature_pinda) start_temp += 5;
  3012. SERIAL_ECHOPGM("start temperature: ");
  3013. MYSERIAL.println(start_temp);
  3014. // setTargetHotend(200, 0);
  3015. setTargetBed(70 + (start_temp - 30));
  3016. custom_message = true;
  3017. custom_message_type = 4;
  3018. custom_message_state = 1;
  3019. custom_message = _T(MSG_TEMP_CALIBRATION);
  3020. current_position[X_AXIS] = PINDA_PREHEAT_X;
  3021. current_position[Y_AXIS] = PINDA_PREHEAT_Y;
  3022. current_position[Z_AXIS] = PINDA_PREHEAT_Z;
  3023. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  3024. st_synchronize();
  3025. while (current_temperature_pinda < start_temp)
  3026. {
  3027. delay_keep_alive(1000);
  3028. serialecho_temperatures();
  3029. }
  3030. eeprom_update_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 0); //invalidate temp. calibration in case that in will be aborted during the calibration process
  3031. current_position[Z_AXIS] = 5;
  3032. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  3033. current_position[X_AXIS] = pgm_read_float(bed_ref_points);
  3034. current_position[Y_AXIS] = pgm_read_float(bed_ref_points + 1);
  3035. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  3036. st_synchronize();
  3037. bool find_z_result = find_bed_induction_sensor_point_z(-1.f);
  3038. if (find_z_result == false) {
  3039. lcd_temp_cal_show_result(find_z_result);
  3040. break;
  3041. }
  3042. zero_z = current_position[Z_AXIS];
  3043. //current_position[Z_AXIS]
  3044. SERIAL_ECHOLNPGM("");
  3045. SERIAL_ECHOPGM("ZERO: ");
  3046. MYSERIAL.print(current_position[Z_AXIS]);
  3047. SERIAL_ECHOLNPGM("");
  3048. int i = -1; for (; i < 5; i++)
  3049. {
  3050. float temp = (40 + i * 5);
  3051. SERIAL_ECHOPGM("Step: ");
  3052. MYSERIAL.print(i + 2);
  3053. SERIAL_ECHOLNPGM("/6 (skipped)");
  3054. SERIAL_ECHOPGM("PINDA temperature: ");
  3055. MYSERIAL.print((40 + i*5));
  3056. SERIAL_ECHOPGM(" Z shift (mm):");
  3057. MYSERIAL.print(0);
  3058. SERIAL_ECHOLNPGM("");
  3059. if (i >= 0) EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + i * 2, &z_shift);
  3060. if (start_temp <= temp) break;
  3061. }
  3062. for (i++; i < 5; i++)
  3063. {
  3064. float temp = (40 + i * 5);
  3065. SERIAL_ECHOPGM("Step: ");
  3066. MYSERIAL.print(i + 2);
  3067. SERIAL_ECHOLNPGM("/6");
  3068. custom_message_state = i + 2;
  3069. setTargetBed(50 + 10 * (temp - 30) / 5);
  3070. // setTargetHotend(255, 0);
  3071. current_position[X_AXIS] = PINDA_PREHEAT_X;
  3072. current_position[Y_AXIS] = PINDA_PREHEAT_Y;
  3073. current_position[Z_AXIS] = PINDA_PREHEAT_Z;
  3074. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  3075. st_synchronize();
  3076. while (current_temperature_pinda < temp)
  3077. {
  3078. delay_keep_alive(1000);
  3079. serialecho_temperatures();
  3080. }
  3081. current_position[Z_AXIS] = 5;
  3082. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  3083. current_position[X_AXIS] = pgm_read_float(bed_ref_points);
  3084. current_position[Y_AXIS] = pgm_read_float(bed_ref_points + 1);
  3085. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  3086. st_synchronize();
  3087. find_z_result = find_bed_induction_sensor_point_z(-1.f);
  3088. if (find_z_result == false) {
  3089. lcd_temp_cal_show_result(find_z_result);
  3090. break;
  3091. }
  3092. z_shift = (int)((current_position[Z_AXIS] - zero_z)*axis_steps_per_unit[Z_AXIS]);
  3093. SERIAL_ECHOLNPGM("");
  3094. SERIAL_ECHOPGM("PINDA temperature: ");
  3095. MYSERIAL.print(current_temperature_pinda);
  3096. SERIAL_ECHOPGM(" Z shift (mm):");
  3097. MYSERIAL.print(current_position[Z_AXIS] - zero_z);
  3098. SERIAL_ECHOLNPGM("");
  3099. EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + i * 2, &z_shift);
  3100. }
  3101. lcd_temp_cal_show_result(true);
  3102. break;
  3103. }
  3104. #endif //PINDA_THERMISTOR
  3105. setTargetBed(PINDA_MIN_T);
  3106. float zero_z;
  3107. int z_shift = 0; //unit: steps
  3108. int t_c; // temperature
  3109. if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS])) {
  3110. // We don't know where we are! HOME!
  3111. // Push the commands to the front of the message queue in the reverse order!
  3112. // There shall be always enough space reserved for these commands.
  3113. repeatcommand_front(); // repeat G76 with all its parameters
  3114. enquecommand_front_P((PSTR("G28 W0")));
  3115. break;
  3116. }
  3117. SERIAL_ECHOLNPGM("PINDA probe calibration start");
  3118. custom_message = true;
  3119. custom_message_type = 4;
  3120. custom_message_state = 1;
  3121. custom_message = _T(MSG_TEMP_CALIBRATION);
  3122. current_position[X_AXIS] = PINDA_PREHEAT_X;
  3123. current_position[Y_AXIS] = PINDA_PREHEAT_Y;
  3124. current_position[Z_AXIS] = PINDA_PREHEAT_Z;
  3125. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  3126. st_synchronize();
  3127. while (abs(degBed() - PINDA_MIN_T) > 1) {
  3128. delay_keep_alive(1000);
  3129. serialecho_temperatures();
  3130. }
  3131. //enquecommand_P(PSTR("M190 S50"));
  3132. for (int i = 0; i < PINDA_HEAT_T; i++) {
  3133. delay_keep_alive(1000);
  3134. serialecho_temperatures();
  3135. }
  3136. eeprom_update_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 0); //invalidate temp. calibration in case that in will be aborted during the calibration process
  3137. current_position[Z_AXIS] = 5;
  3138. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  3139. current_position[X_AXIS] = pgm_read_float(bed_ref_points);
  3140. current_position[Y_AXIS] = pgm_read_float(bed_ref_points + 1);
  3141. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  3142. st_synchronize();
  3143. find_bed_induction_sensor_point_z(-1.f);
  3144. zero_z = current_position[Z_AXIS];
  3145. //current_position[Z_AXIS]
  3146. SERIAL_ECHOLNPGM("");
  3147. SERIAL_ECHOPGM("ZERO: ");
  3148. MYSERIAL.print(current_position[Z_AXIS]);
  3149. SERIAL_ECHOLNPGM("");
  3150. for (int i = 0; i<5; i++) {
  3151. SERIAL_ECHOPGM("Step: ");
  3152. MYSERIAL.print(i+2);
  3153. SERIAL_ECHOLNPGM("/6");
  3154. custom_message_state = i + 2;
  3155. t_c = 60 + i * 10;
  3156. setTargetBed(t_c);
  3157. current_position[X_AXIS] = PINDA_PREHEAT_X;
  3158. current_position[Y_AXIS] = PINDA_PREHEAT_Y;
  3159. current_position[Z_AXIS] = PINDA_PREHEAT_Z;
  3160. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  3161. st_synchronize();
  3162. while (degBed() < t_c) {
  3163. delay_keep_alive(1000);
  3164. serialecho_temperatures();
  3165. }
  3166. for (int i = 0; i < PINDA_HEAT_T; i++) {
  3167. delay_keep_alive(1000);
  3168. serialecho_temperatures();
  3169. }
  3170. current_position[Z_AXIS] = 5;
  3171. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  3172. current_position[X_AXIS] = pgm_read_float(bed_ref_points);
  3173. current_position[Y_AXIS] = pgm_read_float(bed_ref_points + 1);
  3174. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  3175. st_synchronize();
  3176. find_bed_induction_sensor_point_z(-1.f);
  3177. z_shift = (int)((current_position[Z_AXIS] - zero_z)*axis_steps_per_unit[Z_AXIS]);
  3178. SERIAL_ECHOLNPGM("");
  3179. SERIAL_ECHOPGM("Temperature: ");
  3180. MYSERIAL.print(t_c);
  3181. SERIAL_ECHOPGM(" Z shift (mm):");
  3182. MYSERIAL.print(current_position[Z_AXIS] - zero_z);
  3183. SERIAL_ECHOLNPGM("");
  3184. EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + i*2, &z_shift);
  3185. }
  3186. custom_message_type = 0;
  3187. custom_message = false;
  3188. eeprom_update_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 1);
  3189. SERIAL_ECHOLNPGM("Temperature calibration done. Continue with pressing the knob.");
  3190. disable_x();
  3191. disable_y();
  3192. disable_z();
  3193. disable_e0();
  3194. disable_e1();
  3195. disable_e2();
  3196. setTargetBed(0); //set bed target temperature back to 0
  3197. lcd_show_fullscreen_message_and_wait_P(_T(MSG_TEMP_CALIBRATION_DONE));
  3198. temp_cal_active = true;
  3199. eeprom_update_byte((unsigned char *)EEPROM_TEMP_CAL_ACTIVE, 1);
  3200. lcd_update_enable(true);
  3201. lcd_update(2);
  3202. }
  3203. break;
  3204. #ifdef DIS
  3205. case 77:
  3206. {
  3207. //G77 X200 Y150 XP100 YP15 XO10 Y015
  3208. //for 9 point mesh bed leveling G77 X203 Y196 XP3 YP3 XO0 YO0
  3209. //G77 X232 Y218 XP116 YP109 XO-11 YO0
  3210. float dimension_x = 40;
  3211. float dimension_y = 40;
  3212. int points_x = 40;
  3213. int points_y = 40;
  3214. float offset_x = 74;
  3215. float offset_y = 33;
  3216. if (code_seen('X')) dimension_x = code_value();
  3217. if (code_seen('Y')) dimension_y = code_value();
  3218. if (code_seen('XP')) points_x = code_value();
  3219. if (code_seen('YP')) points_y = code_value();
  3220. if (code_seen('XO')) offset_x = code_value();
  3221. if (code_seen('YO')) offset_y = code_value();
  3222. bed_analysis(dimension_x,dimension_y,points_x,points_y,offset_x,offset_y);
  3223. } break;
  3224. #endif
  3225. case 79: {
  3226. for (int i = 255; i > 0; i = i - 5) {
  3227. fanSpeed = i;
  3228. //delay_keep_alive(2000);
  3229. for (int j = 0; j < 100; j++) {
  3230. delay_keep_alive(100);
  3231. }
  3232. fan_speed[1];
  3233. MYSERIAL.print(i); SERIAL_ECHOPGM(": "); MYSERIAL.println(fan_speed[1]);
  3234. }
  3235. }break;
  3236. /**
  3237. * G80: Mesh-based Z probe, probes a grid and produces a
  3238. * mesh to compensate for variable bed height
  3239. *
  3240. * The S0 report the points as below
  3241. *
  3242. * +----> X-axis
  3243. * |
  3244. * |
  3245. * v Y-axis
  3246. *
  3247. */
  3248. case 80:
  3249. #ifdef MK1BP
  3250. break;
  3251. #endif //MK1BP
  3252. case_G80:
  3253. {
  3254. #ifdef TMC2130
  3255. //previously enqueued "G28 W0" failed (crash Z)
  3256. if (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && !axis_known_position[Z_AXIS] && (READ(Z_TMC2130_DIAG) != 0))
  3257. {
  3258. kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW));
  3259. break;
  3260. }
  3261. #endif //TMC2130
  3262. mesh_bed_leveling_flag = true;
  3263. int8_t verbosity_level = 0;
  3264. static bool run = false;
  3265. if (code_seen('V')) {
  3266. // Just 'V' without a number counts as V1.
  3267. char c = strchr_pointer[1];
  3268. verbosity_level = (c == ' ' || c == '\t' || c == 0) ? 1 : code_value_short();
  3269. }
  3270. // Firstly check if we know where we are
  3271. if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS])) {
  3272. // We don't know where we are! HOME!
  3273. // Push the commands to the front of the message queue in the reverse order!
  3274. // There shall be always enough space reserved for these commands.
  3275. if (lcd_commands_type != LCD_COMMAND_STOP_PRINT) {
  3276. repeatcommand_front(); // repeat G80 with all its parameters
  3277. enquecommand_front_P((PSTR("G28 W0")));
  3278. }
  3279. else {
  3280. mesh_bed_leveling_flag = false;
  3281. }
  3282. break;
  3283. }
  3284. bool temp_comp_start = true;
  3285. #ifdef PINDA_THERMISTOR
  3286. temp_comp_start = false;
  3287. #endif //PINDA_THERMISTOR
  3288. if (temp_comp_start)
  3289. if (run == false && temp_cal_active == true && calibration_status_pinda() == true && target_temperature_bed >= 50) {
  3290. if (lcd_commands_type != LCD_COMMAND_STOP_PRINT) {
  3291. temp_compensation_start();
  3292. run = true;
  3293. repeatcommand_front(); // repeat G80 with all its parameters
  3294. enquecommand_front_P((PSTR("G28 W0")));
  3295. }
  3296. else {
  3297. mesh_bed_leveling_flag = false;
  3298. }
  3299. break;
  3300. }
  3301. run = false;
  3302. if (lcd_commands_type == LCD_COMMAND_STOP_PRINT) {
  3303. mesh_bed_leveling_flag = false;
  3304. break;
  3305. }
  3306. // Save custom message state, set a new custom message state to display: Calibrating point 9.
  3307. bool custom_message_old = custom_message;
  3308. unsigned int custom_message_type_old = custom_message_type;
  3309. unsigned int custom_message_state_old = custom_message_state;
  3310. custom_message = true;
  3311. custom_message_type = 1;
  3312. custom_message_state = (MESH_MEAS_NUM_X_POINTS * MESH_MEAS_NUM_Y_POINTS) + 10;
  3313. lcd_update(1);
  3314. mbl.reset(); //reset mesh bed leveling
  3315. // Reset baby stepping to zero, if the babystepping has already been loaded before. The babystepsTodo value will be
  3316. // consumed during the first movements following this statement.
  3317. babystep_undo();
  3318. // Cycle through all points and probe them
  3319. // First move up. During this first movement, the babystepping will be reverted.
  3320. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  3321. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 60, active_extruder);
  3322. // The move to the first calibration point.
  3323. current_position[X_AXIS] = pgm_read_float(bed_ref_points);
  3324. current_position[Y_AXIS] = pgm_read_float(bed_ref_points + 1);
  3325. bool clamped = world2machine_clamp(current_position[X_AXIS], current_position[Y_AXIS]);
  3326. #ifdef SUPPORT_VERBOSITY
  3327. if (verbosity_level >= 1) {
  3328. clamped ? SERIAL_PROTOCOLPGM("First calibration point clamped.\n") : SERIAL_PROTOCOLPGM("No clamping for first calibration point.\n");
  3329. }
  3330. #endif //SUPPORT_VERBOSITY
  3331. // mbl.get_meas_xy(0, 0, current_position[X_AXIS], current_position[Y_AXIS], false);
  3332. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[X_AXIS] / 30, active_extruder);
  3333. // Wait until the move is finished.
  3334. st_synchronize();
  3335. int mesh_point = 0; //index number of calibration point
  3336. int ix = 0;
  3337. int iy = 0;
  3338. int XY_AXIS_FEEDRATE = homing_feedrate[X_AXIS] / 20;
  3339. int Z_PROBE_FEEDRATE = homing_feedrate[Z_AXIS] / 60;
  3340. int Z_LIFT_FEEDRATE = homing_feedrate[Z_AXIS] / 40;
  3341. bool has_z = is_bed_z_jitter_data_valid(); //checks if we have data from Z calibration (offsets of the Z heiths of the 8 calibration points from the first point)
  3342. #ifdef SUPPORT_VERBOSITY
  3343. if (verbosity_level >= 1) {
  3344. has_z ? SERIAL_PROTOCOLPGM("Z jitter data from Z cal. valid.\n") : SERIAL_PROTOCOLPGM("Z jitter data from Z cal. not valid.\n");
  3345. }
  3346. #endif // SUPPORT_VERBOSITY
  3347. setup_for_endstop_move(false); //save feedrate and feedmultiply, sets feedmultiply to 100
  3348. const char *kill_message = NULL;
  3349. while (mesh_point != MESH_MEAS_NUM_X_POINTS * MESH_MEAS_NUM_Y_POINTS) {
  3350. // Get coords of a measuring point.
  3351. ix = mesh_point % MESH_MEAS_NUM_X_POINTS; // from 0 to MESH_NUM_X_POINTS - 1
  3352. iy = mesh_point / MESH_MEAS_NUM_X_POINTS;
  3353. if (iy & 1) ix = (MESH_MEAS_NUM_X_POINTS - 1) - ix; // Zig zag
  3354. float z0 = 0.f;
  3355. if (has_z && mesh_point > 0) {
  3356. uint16_t z_offset_u = eeprom_read_word((uint16_t*)(EEPROM_BED_CALIBRATION_Z_JITTER + 2 * (ix + iy * 3 - 1)));
  3357. z0 = mbl.z_values[0][0] + *reinterpret_cast<int16_t*>(&z_offset_u) * 0.01;
  3358. //#if 0
  3359. #ifdef SUPPORT_VERBOSITY
  3360. if (verbosity_level >= 1) {
  3361. SERIAL_ECHOLNPGM("");
  3362. SERIAL_ECHOPGM("Bed leveling, point: ");
  3363. MYSERIAL.print(mesh_point);
  3364. SERIAL_ECHOPGM(", calibration z: ");
  3365. MYSERIAL.print(z0, 5);
  3366. SERIAL_ECHOLNPGM("");
  3367. }
  3368. #endif // SUPPORT_VERBOSITY
  3369. //#endif
  3370. }
  3371. // Move Z up to MESH_HOME_Z_SEARCH.
  3372. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  3373. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], Z_LIFT_FEEDRATE, active_extruder);
  3374. st_synchronize();
  3375. // Move to XY position of the sensor point.
  3376. current_position[X_AXIS] = pgm_read_float(bed_ref_points + 2 * mesh_point);
  3377. current_position[Y_AXIS] = pgm_read_float(bed_ref_points + 2 * mesh_point + 1);
  3378. world2machine_clamp(current_position[X_AXIS], current_position[Y_AXIS]);
  3379. #ifdef SUPPORT_VERBOSITY
  3380. if (verbosity_level >= 1) {
  3381. SERIAL_PROTOCOL(mesh_point);
  3382. clamped ? SERIAL_PROTOCOLPGM(": xy clamped.\n") : SERIAL_PROTOCOLPGM(": no xy clamping\n");
  3383. }
  3384. #endif // SUPPORT_VERBOSITY
  3385. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], XY_AXIS_FEEDRATE, active_extruder);
  3386. st_synchronize();
  3387. // Go down until endstop is hit
  3388. const float Z_CALIBRATION_THRESHOLD = 1.f;
  3389. if (!find_bed_induction_sensor_point_z((has_z && mesh_point > 0) ? z0 - Z_CALIBRATION_THRESHOLD : -10.f)) { //if we have data from z calibration max allowed difference is 1mm for each point, if we dont have data max difference is 10mm from initial point
  3390. kill_message = _T(MSG_BED_LEVELING_FAILED_POINT_LOW);
  3391. break;
  3392. }
  3393. if (MESH_HOME_Z_SEARCH - current_position[Z_AXIS] < 0.1f) {
  3394. kill_message = _i("Bed leveling failed. Sensor disconnected or cable broken. Waiting for reset.");////MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED c=20 r=4
  3395. break;
  3396. }
  3397. if (has_z && fabs(z0 - current_position[Z_AXIS]) > Z_CALIBRATION_THRESHOLD) { //if we have data from z calibration, max. allowed difference is 1mm for each point
  3398. kill_message = _i("Bed leveling failed. Sensor triggered too high. Waiting for reset.");////MSG_BED_LEVELING_FAILED_POINT_HIGH c=20 r=4
  3399. break;
  3400. }
  3401. #ifdef SUPPORT_VERBOSITY
  3402. if (verbosity_level >= 10) {
  3403. SERIAL_ECHOPGM("X: ");
  3404. MYSERIAL.print(current_position[X_AXIS], 5);
  3405. SERIAL_ECHOLNPGM("");
  3406. SERIAL_ECHOPGM("Y: ");
  3407. MYSERIAL.print(current_position[Y_AXIS], 5);
  3408. SERIAL_PROTOCOLPGM("\n");
  3409. }
  3410. #endif // SUPPORT_VERBOSITY
  3411. float offset_z = 0;
  3412. #ifdef PINDA_THERMISTOR
  3413. offset_z = temp_compensation_pinda_thermistor_offset(current_temperature_pinda);
  3414. #endif //PINDA_THERMISTOR
  3415. // #ifdef SUPPORT_VERBOSITY
  3416. /* if (verbosity_level >= 1)
  3417. {
  3418. SERIAL_ECHOPGM("mesh bed leveling: ");
  3419. MYSERIAL.print(current_position[Z_AXIS], 5);
  3420. SERIAL_ECHOPGM(" offset: ");
  3421. MYSERIAL.print(offset_z, 5);
  3422. SERIAL_ECHOLNPGM("");
  3423. }*/
  3424. // #endif // SUPPORT_VERBOSITY
  3425. mbl.set_z(ix, iy, current_position[Z_AXIS] - offset_z); //store measured z values z_values[iy][ix] = z - offset_z;
  3426. custom_message_state--;
  3427. mesh_point++;
  3428. lcd_update(1);
  3429. }
  3430. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  3431. #ifdef SUPPORT_VERBOSITY
  3432. if (verbosity_level >= 20) {
  3433. SERIAL_ECHOLNPGM("Mesh bed leveling while loop finished.");
  3434. SERIAL_ECHOLNPGM("MESH_HOME_Z_SEARCH: ");
  3435. MYSERIAL.print(current_position[Z_AXIS], 5);
  3436. }
  3437. #endif // SUPPORT_VERBOSITY
  3438. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], Z_LIFT_FEEDRATE, active_extruder);
  3439. st_synchronize();
  3440. if (mesh_point != MESH_MEAS_NUM_X_POINTS * MESH_MEAS_NUM_Y_POINTS) {
  3441. kill(kill_message);
  3442. SERIAL_ECHOLNPGM("killed");
  3443. }
  3444. clean_up_after_endstop_move();
  3445. // SERIAL_ECHOLNPGM("clean up finished ");
  3446. bool apply_temp_comp = true;
  3447. #ifdef PINDA_THERMISTOR
  3448. apply_temp_comp = false;
  3449. #endif
  3450. if (apply_temp_comp)
  3451. if(temp_cal_active == true && calibration_status_pinda() == true) temp_compensation_apply(); //apply PINDA temperature compensation
  3452. babystep_apply(); // Apply Z height correction aka baby stepping before mesh bed leveing gets activated.
  3453. // SERIAL_ECHOLNPGM("babystep applied");
  3454. bool eeprom_bed_correction_valid = eeprom_read_byte((unsigned char*)EEPROM_BED_CORRECTION_VALID) == 1;
  3455. #ifdef SUPPORT_VERBOSITY
  3456. if (verbosity_level >= 1) {
  3457. eeprom_bed_correction_valid ? SERIAL_PROTOCOLPGM("Bed correction data valid\n") : SERIAL_PROTOCOLPGM("Bed correction data not valid\n");
  3458. }
  3459. #endif // SUPPORT_VERBOSITY
  3460. for (uint8_t i = 0; i < 4; ++i) {
  3461. unsigned char codes[4] = { 'L', 'R', 'F', 'B' };
  3462. long correction = 0;
  3463. if (code_seen(codes[i]))
  3464. correction = code_value_long();
  3465. else if (eeprom_bed_correction_valid) {
  3466. unsigned char *addr = (i < 2) ?
  3467. ((i == 0) ? (unsigned char*)EEPROM_BED_CORRECTION_LEFT : (unsigned char*)EEPROM_BED_CORRECTION_RIGHT) :
  3468. ((i == 2) ? (unsigned char*)EEPROM_BED_CORRECTION_FRONT : (unsigned char*)EEPROM_BED_CORRECTION_REAR);
  3469. correction = eeprom_read_int8(addr);
  3470. }
  3471. if (correction == 0)
  3472. continue;
  3473. float offset = float(correction) * 0.001f;
  3474. if (fabs(offset) > 0.101f) {
  3475. SERIAL_ERROR_START;
  3476. SERIAL_ECHOPGM("Excessive bed leveling correction: ");
  3477. SERIAL_ECHO(offset);
  3478. SERIAL_ECHOLNPGM(" microns");
  3479. }
  3480. else {
  3481. switch (i) {
  3482. case 0:
  3483. for (uint8_t row = 0; row < 3; ++row) {
  3484. mbl.z_values[row][1] += 0.5f * offset;
  3485. mbl.z_values[row][0] += offset;
  3486. }
  3487. break;
  3488. case 1:
  3489. for (uint8_t row = 0; row < 3; ++row) {
  3490. mbl.z_values[row][1] += 0.5f * offset;
  3491. mbl.z_values[row][2] += offset;
  3492. }
  3493. break;
  3494. case 2:
  3495. for (uint8_t col = 0; col < 3; ++col) {
  3496. mbl.z_values[1][col] += 0.5f * offset;
  3497. mbl.z_values[0][col] += offset;
  3498. }
  3499. break;
  3500. case 3:
  3501. for (uint8_t col = 0; col < 3; ++col) {
  3502. mbl.z_values[1][col] += 0.5f * offset;
  3503. mbl.z_values[2][col] += offset;
  3504. }
  3505. break;
  3506. }
  3507. }
  3508. }
  3509. // SERIAL_ECHOLNPGM("Bed leveling correction finished");
  3510. mbl.upsample_3x3(); //bilinear interpolation from 3x3 to 7x7 points while using the same array z_values[iy][ix] for storing (just coppying measured data to new destination and interpolating between them)
  3511. // SERIAL_ECHOLNPGM("Upsample finished");
  3512. mbl.active = 1; //activate mesh bed leveling
  3513. // SERIAL_ECHOLNPGM("Mesh bed leveling activated");
  3514. go_home_with_z_lift();
  3515. // SERIAL_ECHOLNPGM("Go home finished");
  3516. //unretract (after PINDA preheat retraction)
  3517. if (degHotend(active_extruder) > EXTRUDE_MINTEMP && temp_cal_active == true && calibration_status_pinda() == true && target_temperature_bed >= 50) {
  3518. current_position[E_AXIS] += DEFAULT_RETRACTION;
  3519. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 400, active_extruder);
  3520. }
  3521. KEEPALIVE_STATE(NOT_BUSY);
  3522. // Restore custom message state
  3523. custom_message = custom_message_old;
  3524. custom_message_type = custom_message_type_old;
  3525. custom_message_state = custom_message_state_old;
  3526. mesh_bed_leveling_flag = false;
  3527. mesh_bed_run_from_menu = false;
  3528. lcd_update(2);
  3529. }
  3530. break;
  3531. /**
  3532. * G81: Print mesh bed leveling status and bed profile if activated
  3533. */
  3534. case 81:
  3535. if (mbl.active) {
  3536. SERIAL_PROTOCOLPGM("Num X,Y: ");
  3537. SERIAL_PROTOCOL(MESH_NUM_X_POINTS);
  3538. SERIAL_PROTOCOLPGM(",");
  3539. SERIAL_PROTOCOL(MESH_NUM_Y_POINTS);
  3540. SERIAL_PROTOCOLPGM("\nZ search height: ");
  3541. SERIAL_PROTOCOL(MESH_HOME_Z_SEARCH);
  3542. SERIAL_PROTOCOLLNPGM("\nMeasured points:");
  3543. for (int y = MESH_NUM_Y_POINTS-1; y >= 0; y--) {
  3544. for (int x = 0; x < MESH_NUM_X_POINTS; x++) {
  3545. SERIAL_PROTOCOLPGM(" ");
  3546. SERIAL_PROTOCOL_F(mbl.z_values[y][x], 5);
  3547. }
  3548. SERIAL_PROTOCOLPGM("\n");
  3549. }
  3550. }
  3551. else
  3552. SERIAL_PROTOCOLLNPGM("Mesh bed leveling not active.");
  3553. break;
  3554. #if 0
  3555. /**
  3556. * G82: Single Z probe at current location
  3557. *
  3558. * WARNING! USE WITH CAUTION! If you'll try to probe where is no leveling pad, nasty things can happen!
  3559. *
  3560. */
  3561. case 82:
  3562. SERIAL_PROTOCOLLNPGM("Finding bed ");
  3563. setup_for_endstop_move();
  3564. find_bed_induction_sensor_point_z();
  3565. clean_up_after_endstop_move();
  3566. SERIAL_PROTOCOLPGM("Bed found at: ");
  3567. SERIAL_PROTOCOL_F(current_position[Z_AXIS], 5);
  3568. SERIAL_PROTOCOLPGM("\n");
  3569. break;
  3570. /**
  3571. * G83: Prusa3D specific: Babystep in Z and store to EEPROM
  3572. */
  3573. case 83:
  3574. {
  3575. int babystepz = code_seen('S') ? code_value() : 0;
  3576. int BabyPosition = code_seen('P') ? code_value() : 0;
  3577. if (babystepz != 0) {
  3578. //FIXME Vojtech: What shall be the index of the axis Z: 3 or 4?
  3579. // Is the axis indexed starting with zero or one?
  3580. if (BabyPosition > 4) {
  3581. SERIAL_PROTOCOLLNPGM("Index out of bounds");
  3582. }else{
  3583. // Save it to the eeprom
  3584. babystepLoadZ = babystepz;
  3585. EEPROM_save_B(EEPROM_BABYSTEP_Z0+(BabyPosition*2),&babystepLoadZ);
  3586. // adjust the Z
  3587. babystepsTodoZadd(babystepLoadZ);
  3588. }
  3589. }
  3590. }
  3591. break;
  3592. /**
  3593. * G84: Prusa3D specific: UNDO Babystep Z (move Z axis back)
  3594. */
  3595. case 84:
  3596. babystepsTodoZsubtract(babystepLoadZ);
  3597. // babystepLoadZ = 0;
  3598. break;
  3599. /**
  3600. * G85: Prusa3D specific: Pick best babystep
  3601. */
  3602. case 85:
  3603. lcd_pick_babystep();
  3604. break;
  3605. #endif
  3606. /**
  3607. * G86: Prusa3D specific: Disable babystep correction after home.
  3608. * This G-code will be performed at the start of a calibration script.
  3609. */
  3610. case 86:
  3611. calibration_status_store(CALIBRATION_STATUS_LIVE_ADJUST);
  3612. break;
  3613. /**
  3614. * G87: Prusa3D specific: Enable babystep correction after home
  3615. * This G-code will be performed at the end of a calibration script.
  3616. */
  3617. case 87:
  3618. calibration_status_store(CALIBRATION_STATUS_CALIBRATED);
  3619. break;
  3620. /**
  3621. * G88: Prusa3D specific: Don't know what it is for, it is in V2Calibration.gcode
  3622. */
  3623. case 88:
  3624. break;
  3625. #endif // ENABLE_MESH_BED_LEVELING
  3626. case 90: // G90
  3627. relative_mode = false;
  3628. break;
  3629. case 91: // G91
  3630. relative_mode = true;
  3631. break;
  3632. case 92: // G92
  3633. if(!code_seen(axis_codes[E_AXIS]))
  3634. st_synchronize();
  3635. for(int8_t i=0; i < NUM_AXIS; i++) {
  3636. if(code_seen(axis_codes[i])) {
  3637. if(i == E_AXIS) {
  3638. current_position[i] = code_value();
  3639. plan_set_e_position(current_position[E_AXIS]);
  3640. }
  3641. else {
  3642. current_position[i] = code_value()+add_homing[i];
  3643. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  3644. }
  3645. }
  3646. }
  3647. break;
  3648. case 98: // G98 (activate farm mode)
  3649. farm_mode = 1;
  3650. PingTime = millis();
  3651. eeprom_update_byte((unsigned char *)EEPROM_FARM_MODE, farm_mode);
  3652. SilentModeMenu = SILENT_MODE_OFF;
  3653. eeprom_update_byte((unsigned char *)EEPROM_SILENT, SilentModeMenu);
  3654. break;
  3655. case 99: // G99 (deactivate farm mode)
  3656. farm_mode = 0;
  3657. lcd_printer_connected();
  3658. eeprom_update_byte((unsigned char *)EEPROM_FARM_MODE, farm_mode);
  3659. lcd_update(2);
  3660. break;
  3661. default:
  3662. printf_P(PSTR("Unknown G code: %s \n"), cmdbuffer + bufindr + CMDHDRSIZE);
  3663. }
  3664. } // end if(code_seen('G'))
  3665. else if(code_seen('M'))
  3666. {
  3667. int index;
  3668. for (index = 1; *(strchr_pointer + index) == ' ' || *(strchr_pointer + index) == '\t'; index++);
  3669. /*for (++strchr_pointer; *strchr_pointer == ' ' || *strchr_pointer == '\t'; ++strchr_pointer);*/
  3670. if (*(strchr_pointer+index) < '0' || *(strchr_pointer+index) > '9') {
  3671. printf_P(PSTR("Invalid M code: %s \n"), cmdbuffer + bufindr + CMDHDRSIZE);
  3672. } else
  3673. switch((int)code_value())
  3674. {
  3675. #ifdef ULTIPANEL
  3676. case 0: // M0 - Unconditional stop - Wait for user button press on LCD
  3677. case 1: // M1 - Conditional stop - Wait for user button press on LCD
  3678. {
  3679. char *src = strchr_pointer + 2;
  3680. codenum = 0;
  3681. bool hasP = false, hasS = false;
  3682. if (code_seen('P')) {
  3683. codenum = code_value(); // milliseconds to wait
  3684. hasP = codenum > 0;
  3685. }
  3686. if (code_seen('S')) {
  3687. codenum = code_value() * 1000; // seconds to wait
  3688. hasS = codenum > 0;
  3689. }
  3690. starpos = strchr(src, '*');
  3691. if (starpos != NULL) *(starpos) = '\0';
  3692. while (*src == ' ') ++src;
  3693. if (!hasP && !hasS && *src != '\0') {
  3694. lcd_setstatus(src);
  3695. } else {
  3696. LCD_MESSAGERPGM(_i("Wait for user..."));////MSG_USERWAIT c=0 r=0
  3697. }
  3698. lcd_ignore_click(); //call lcd_ignore_click aslo for else ???
  3699. st_synchronize();
  3700. previous_millis_cmd = millis();
  3701. if (codenum > 0){
  3702. codenum += millis(); // keep track of when we started waiting
  3703. KEEPALIVE_STATE(PAUSED_FOR_USER);
  3704. while(millis() < codenum && !lcd_clicked()){
  3705. manage_heater();
  3706. manage_inactivity(true);
  3707. lcd_update();
  3708. }
  3709. KEEPALIVE_STATE(IN_HANDLER);
  3710. lcd_ignore_click(false);
  3711. }else{
  3712. if (!lcd_detected())
  3713. break;
  3714. KEEPALIVE_STATE(PAUSED_FOR_USER);
  3715. while(!lcd_clicked()){
  3716. manage_heater();
  3717. manage_inactivity(true);
  3718. lcd_update();
  3719. }
  3720. KEEPALIVE_STATE(IN_HANDLER);
  3721. }
  3722. if (IS_SD_PRINTING)
  3723. LCD_MESSAGERPGM(_i("Resuming print"));////MSG_RESUMING c=0 r=0
  3724. else
  3725. LCD_MESSAGERPGM(_T(WELCOME_MSG));
  3726. }
  3727. break;
  3728. #endif
  3729. case 17:
  3730. LCD_MESSAGERPGM(_i("No move."));////MSG_NO_MOVE c=0 r=0
  3731. enable_x();
  3732. enable_y();
  3733. enable_z();
  3734. enable_e0();
  3735. enable_e1();
  3736. enable_e2();
  3737. break;
  3738. #ifdef SDSUPPORT
  3739. case 20: // M20 - list SD card
  3740. SERIAL_PROTOCOLLNRPGM(_i("Begin file list"));////MSG_BEGIN_FILE_LIST c=0 r=0
  3741. card.ls();
  3742. SERIAL_PROTOCOLLNRPGM(_i("End file list"));////MSG_END_FILE_LIST c=0 r=0
  3743. break;
  3744. case 21: // M21 - init SD card
  3745. card.initsd();
  3746. break;
  3747. case 22: //M22 - release SD card
  3748. card.release();
  3749. break;
  3750. case 23: //M23 - Select file
  3751. starpos = (strchr(strchr_pointer + 4,'*'));
  3752. if(starpos!=NULL)
  3753. *(starpos)='\0';
  3754. card.openFile(strchr_pointer + 4,true);
  3755. break;
  3756. case 24: //M24 - Start SD print
  3757. if (!card.paused)
  3758. failstats_reset_print();
  3759. card.startFileprint();
  3760. starttime=millis();
  3761. break;
  3762. case 25: //M25 - Pause SD print
  3763. card.pauseSDPrint();
  3764. break;
  3765. case 26: //M26 - Set SD index
  3766. if(card.cardOK && code_seen('S')) {
  3767. card.setIndex(code_value_long());
  3768. }
  3769. break;
  3770. case 27: //M27 - Get SD status
  3771. card.getStatus();
  3772. break;
  3773. case 28: //M28 - Start SD write
  3774. starpos = (strchr(strchr_pointer + 4,'*'));
  3775. if(starpos != NULL){
  3776. char* npos = strchr(CMDBUFFER_CURRENT_STRING, 'N');
  3777. strchr_pointer = strchr(npos,' ') + 1;
  3778. *(starpos) = '\0';
  3779. }
  3780. card.openFile(strchr_pointer+4,false);
  3781. break;
  3782. case 29: //M29 - Stop SD write
  3783. //processed in write to file routine above
  3784. //card,saving = false;
  3785. break;
  3786. case 30: //M30 <filename> Delete File
  3787. if (card.cardOK){
  3788. card.closefile();
  3789. starpos = (strchr(strchr_pointer + 4,'*'));
  3790. if(starpos != NULL){
  3791. char* npos = strchr(CMDBUFFER_CURRENT_STRING, 'N');
  3792. strchr_pointer = strchr(npos,' ') + 1;
  3793. *(starpos) = '\0';
  3794. }
  3795. card.removeFile(strchr_pointer + 4);
  3796. }
  3797. break;
  3798. case 32: //M32 - Select file and start SD print
  3799. {
  3800. if(card.sdprinting) {
  3801. st_synchronize();
  3802. }
  3803. starpos = (strchr(strchr_pointer + 4,'*'));
  3804. char* namestartpos = (strchr(strchr_pointer + 4,'!')); //find ! to indicate filename string start.
  3805. if(namestartpos==NULL)
  3806. {
  3807. namestartpos=strchr_pointer + 4; //default name position, 4 letters after the M
  3808. }
  3809. else
  3810. namestartpos++; //to skip the '!'
  3811. if(starpos!=NULL)
  3812. *(starpos)='\0';
  3813. bool call_procedure=(code_seen('P'));
  3814. if(strchr_pointer>namestartpos)
  3815. call_procedure=false; //false alert, 'P' found within filename
  3816. if( card.cardOK )
  3817. {
  3818. card.openFile(namestartpos,true,!call_procedure);
  3819. if(code_seen('S'))
  3820. if(strchr_pointer<namestartpos) //only if "S" is occuring _before_ the filename
  3821. card.setIndex(code_value_long());
  3822. card.startFileprint();
  3823. if(!call_procedure)
  3824. starttime=millis(); //procedure calls count as normal print time.
  3825. }
  3826. } break;
  3827. case 928: //M928 - Start SD write
  3828. starpos = (strchr(strchr_pointer + 5,'*'));
  3829. if(starpos != NULL){
  3830. char* npos = strchr(CMDBUFFER_CURRENT_STRING, 'N');
  3831. strchr_pointer = strchr(npos,' ') + 1;
  3832. *(starpos) = '\0';
  3833. }
  3834. card.openLogFile(strchr_pointer+5);
  3835. break;
  3836. #endif //SDSUPPORT
  3837. case 31: //M31 take time since the start of the SD print or an M109 command
  3838. {
  3839. stoptime=millis();
  3840. char time[30];
  3841. unsigned long t=(stoptime-starttime)/1000;
  3842. int sec,min;
  3843. min=t/60;
  3844. sec=t%60;
  3845. sprintf_P(time, PSTR("%i min, %i sec"), min, sec);
  3846. SERIAL_ECHO_START;
  3847. SERIAL_ECHOLN(time);
  3848. lcd_setstatus(time);
  3849. autotempShutdown();
  3850. }
  3851. break;
  3852. #ifndef _DISABLE_M42_M226
  3853. case 42: //M42 -Change pin status via gcode
  3854. if (code_seen('S'))
  3855. {
  3856. int pin_status = code_value();
  3857. int pin_number = LED_PIN;
  3858. if (code_seen('P') && pin_status >= 0 && pin_status <= 255)
  3859. pin_number = code_value();
  3860. for(int8_t i = 0; i < (int8_t)(sizeof(sensitive_pins)/sizeof(int)); i++)
  3861. {
  3862. if (sensitive_pins[i] == pin_number)
  3863. {
  3864. pin_number = -1;
  3865. break;
  3866. }
  3867. }
  3868. #if defined(FAN_PIN) && FAN_PIN > -1
  3869. if (pin_number == FAN_PIN)
  3870. fanSpeed = pin_status;
  3871. #endif
  3872. if (pin_number > -1)
  3873. {
  3874. pinMode(pin_number, OUTPUT);
  3875. digitalWrite(pin_number, pin_status);
  3876. analogWrite(pin_number, pin_status);
  3877. }
  3878. }
  3879. break;
  3880. #endif //_DISABLE_M42_M226
  3881. case 44: // M44: Prusa3D: Reset the bed skew and offset calibration.
  3882. // Reset the baby step value and the baby step applied flag.
  3883. calibration_status_store(CALIBRATION_STATUS_ASSEMBLED);
  3884. eeprom_update_word((uint16_t*)EEPROM_BABYSTEP_Z, 0);
  3885. // Reset the skew and offset in both RAM and EEPROM.
  3886. reset_bed_offset_and_skew();
  3887. // Reset world2machine_rotation_and_skew and world2machine_shift, therefore
  3888. // the planner will not perform any adjustments in the XY plane.
  3889. // Wait for the motors to stop and update the current position with the absolute values.
  3890. world2machine_revert_to_uncorrected();
  3891. break;
  3892. case 45: // M45: Prusa3D: bed skew and offset with manual Z up
  3893. {
  3894. int8_t verbosity_level = 0;
  3895. bool only_Z = code_seen('Z');
  3896. #ifdef SUPPORT_VERBOSITY
  3897. if (code_seen('V'))
  3898. {
  3899. // Just 'V' without a number counts as V1.
  3900. char c = strchr_pointer[1];
  3901. verbosity_level = (c == ' ' || c == '\t' || c == 0) ? 1 : code_value_short();
  3902. }
  3903. #endif //SUPPORT_VERBOSITY
  3904. gcode_M45(only_Z, verbosity_level);
  3905. }
  3906. break;
  3907. /*
  3908. case 46:
  3909. {
  3910. // M46: Prusa3D: Show the assigned IP address.
  3911. uint8_t ip[4];
  3912. bool hasIP = card.ToshibaFlashAir_GetIP(ip);
  3913. if (hasIP) {
  3914. SERIAL_ECHOPGM("Toshiba FlashAir current IP: ");
  3915. SERIAL_ECHO(int(ip[0]));
  3916. SERIAL_ECHOPGM(".");
  3917. SERIAL_ECHO(int(ip[1]));
  3918. SERIAL_ECHOPGM(".");
  3919. SERIAL_ECHO(int(ip[2]));
  3920. SERIAL_ECHOPGM(".");
  3921. SERIAL_ECHO(int(ip[3]));
  3922. SERIAL_ECHOLNPGM("");
  3923. } else {
  3924. SERIAL_ECHOLNPGM("Toshiba FlashAir GetIP failed");
  3925. }
  3926. break;
  3927. }
  3928. */
  3929. case 47:
  3930. // M47: Prusa3D: Show end stops dialog on the display.
  3931. KEEPALIVE_STATE(PAUSED_FOR_USER);
  3932. lcd_diag_show_end_stops();
  3933. KEEPALIVE_STATE(IN_HANDLER);
  3934. break;
  3935. #if 0
  3936. case 48: // M48: scan the bed induction sensor points, print the sensor trigger coordinates to the serial line for visualization on the PC.
  3937. {
  3938. // Disable the default update procedure of the display. We will do a modal dialog.
  3939. lcd_update_enable(false);
  3940. // Let the planner use the uncorrected coordinates.
  3941. mbl.reset();
  3942. // Reset world2machine_rotation_and_skew and world2machine_shift, therefore
  3943. // the planner will not perform any adjustments in the XY plane.
  3944. // Wait for the motors to stop and update the current position with the absolute values.
  3945. world2machine_revert_to_uncorrected();
  3946. // Move the print head close to the bed.
  3947. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  3948. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS],current_position[Z_AXIS] , current_position[E_AXIS], homing_feedrate[Z_AXIS]/40, active_extruder);
  3949. st_synchronize();
  3950. // Home in the XY plane.
  3951. set_destination_to_current();
  3952. setup_for_endstop_move();
  3953. home_xy();
  3954. int8_t verbosity_level = 0;
  3955. if (code_seen('V')) {
  3956. // Just 'V' without a number counts as V1.
  3957. char c = strchr_pointer[1];
  3958. verbosity_level = (c == ' ' || c == '\t' || c == 0) ? 1 : code_value_short();
  3959. }
  3960. bool success = scan_bed_induction_points(verbosity_level);
  3961. clean_up_after_endstop_move();
  3962. // Print head up.
  3963. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  3964. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS],current_position[Z_AXIS] , current_position[E_AXIS], homing_feedrate[Z_AXIS]/40, active_extruder);
  3965. st_synchronize();
  3966. lcd_update_enable(true);
  3967. break;
  3968. }
  3969. #endif
  3970. // M48 Z-Probe repeatability measurement function.
  3971. //
  3972. // Usage: M48 <n #_samples> <X X_position_for_samples> <Y Y_position_for_samples> <V Verbose_Level> <L legs_of_movement_prior_to_doing_probe>
  3973. //
  3974. // This function assumes the bed has been homed. Specificaly, that a G28 command
  3975. // as been issued prior to invoking the M48 Z-Probe repeatability measurement function.
  3976. // Any information generated by a prior G29 Bed leveling command will be lost and need to be
  3977. // regenerated.
  3978. //
  3979. // The number of samples will default to 10 if not specified. You can use upper or lower case
  3980. // letters for any of the options EXCEPT n. n must be in lower case because Marlin uses a capital
  3981. // N for its communication protocol and will get horribly confused if you send it a capital N.
  3982. //
  3983. #ifdef ENABLE_AUTO_BED_LEVELING
  3984. #ifdef Z_PROBE_REPEATABILITY_TEST
  3985. case 48: // M48 Z-Probe repeatability
  3986. {
  3987. #if Z_MIN_PIN == -1
  3988. #error "You must have a Z_MIN endstop in order to enable calculation of Z-Probe repeatability."
  3989. #endif
  3990. double sum=0.0;
  3991. double mean=0.0;
  3992. double sigma=0.0;
  3993. double sample_set[50];
  3994. int verbose_level=1, n=0, j, n_samples = 10, n_legs=0;
  3995. double X_current, Y_current, Z_current;
  3996. double X_probe_location, Y_probe_location, Z_start_location, ext_position;
  3997. if (code_seen('V') || code_seen('v')) {
  3998. verbose_level = code_value();
  3999. if (verbose_level<0 || verbose_level>4 ) {
  4000. SERIAL_PROTOCOLPGM("?Verbose Level not plausable.\n");
  4001. goto Sigma_Exit;
  4002. }
  4003. }
  4004. if (verbose_level > 0) {
  4005. SERIAL_PROTOCOLPGM("M48 Z-Probe Repeatability test. Version 2.00\n");
  4006. SERIAL_PROTOCOLPGM("Full support at: http://3dprintboard.com/forum.php\n");
  4007. }
  4008. if (code_seen('n')) {
  4009. n_samples = code_value();
  4010. if (n_samples<4 || n_samples>50 ) {
  4011. SERIAL_PROTOCOLPGM("?Specified sample size not plausable.\n");
  4012. goto Sigma_Exit;
  4013. }
  4014. }
  4015. X_current = X_probe_location = st_get_position_mm(X_AXIS);
  4016. Y_current = Y_probe_location = st_get_position_mm(Y_AXIS);
  4017. Z_current = st_get_position_mm(Z_AXIS);
  4018. Z_start_location = st_get_position_mm(Z_AXIS) + Z_RAISE_BEFORE_PROBING;
  4019. ext_position = st_get_position_mm(E_AXIS);
  4020. if (code_seen('X') || code_seen('x') ) {
  4021. X_probe_location = code_value() - X_PROBE_OFFSET_FROM_EXTRUDER;
  4022. if (X_probe_location<X_MIN_POS || X_probe_location>X_MAX_POS ) {
  4023. SERIAL_PROTOCOLPGM("?Specified X position out of range.\n");
  4024. goto Sigma_Exit;
  4025. }
  4026. }
  4027. if (code_seen('Y') || code_seen('y') ) {
  4028. Y_probe_location = code_value() - Y_PROBE_OFFSET_FROM_EXTRUDER;
  4029. if (Y_probe_location<Y_MIN_POS || Y_probe_location>Y_MAX_POS ) {
  4030. SERIAL_PROTOCOLPGM("?Specified Y position out of range.\n");
  4031. goto Sigma_Exit;
  4032. }
  4033. }
  4034. if (code_seen('L') || code_seen('l') ) {
  4035. n_legs = code_value();
  4036. if ( n_legs==1 )
  4037. n_legs = 2;
  4038. if ( n_legs<0 || n_legs>15 ) {
  4039. SERIAL_PROTOCOLPGM("?Specified number of legs in movement not plausable.\n");
  4040. goto Sigma_Exit;
  4041. }
  4042. }
  4043. //
  4044. // Do all the preliminary setup work. First raise the probe.
  4045. //
  4046. st_synchronize();
  4047. plan_bed_level_matrix.set_to_identity();
  4048. plan_buffer_line( X_current, Y_current, Z_start_location,
  4049. ext_position,
  4050. homing_feedrate[Z_AXIS]/60,
  4051. active_extruder);
  4052. st_synchronize();
  4053. //
  4054. // Now get everything to the specified probe point So we can safely do a probe to
  4055. // get us close to the bed. If the Z-Axis is far from the bed, we don't want to
  4056. // use that as a starting point for each probe.
  4057. //
  4058. if (verbose_level > 2)
  4059. SERIAL_PROTOCOL("Positioning probe for the test.\n");
  4060. plan_buffer_line( X_probe_location, Y_probe_location, Z_start_location,
  4061. ext_position,
  4062. homing_feedrate[X_AXIS]/60,
  4063. active_extruder);
  4064. st_synchronize();
  4065. current_position[X_AXIS] = X_current = st_get_position_mm(X_AXIS);
  4066. current_position[Y_AXIS] = Y_current = st_get_position_mm(Y_AXIS);
  4067. current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS);
  4068. current_position[E_AXIS] = ext_position = st_get_position_mm(E_AXIS);
  4069. //
  4070. // OK, do the inital probe to get us close to the bed.
  4071. // Then retrace the right amount and use that in subsequent probes
  4072. //
  4073. setup_for_endstop_move();
  4074. run_z_probe();
  4075. current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS);
  4076. Z_start_location = st_get_position_mm(Z_AXIS) + Z_RAISE_BEFORE_PROBING;
  4077. plan_buffer_line( X_probe_location, Y_probe_location, Z_start_location,
  4078. ext_position,
  4079. homing_feedrate[X_AXIS]/60,
  4080. active_extruder);
  4081. st_synchronize();
  4082. current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS);
  4083. for( n=0; n<n_samples; n++) {
  4084. do_blocking_move_to( X_probe_location, Y_probe_location, Z_start_location); // Make sure we are at the probe location
  4085. if ( n_legs) {
  4086. double radius=0.0, theta=0.0, x_sweep, y_sweep;
  4087. int rotational_direction, l;
  4088. rotational_direction = (unsigned long) millis() & 0x0001; // clockwise or counter clockwise
  4089. radius = (unsigned long) millis() % (long) (X_MAX_LENGTH/4); // limit how far out to go
  4090. theta = (float) ((unsigned long) millis() % (long) 360) / (360./(2*3.1415926)); // turn into radians
  4091. //SERIAL_ECHOPAIR("starting radius: ",radius);
  4092. //SERIAL_ECHOPAIR(" theta: ",theta);
  4093. //SERIAL_ECHOPAIR(" direction: ",rotational_direction);
  4094. //SERIAL_PROTOCOLLNPGM("");
  4095. for( l=0; l<n_legs-1; l++) {
  4096. if (rotational_direction==1)
  4097. theta += (float) ((unsigned long) millis() % (long) 20) / (360.0/(2*3.1415926)); // turn into radians
  4098. else
  4099. theta -= (float) ((unsigned long) millis() % (long) 20) / (360.0/(2*3.1415926)); // turn into radians
  4100. radius += (float) ( ((long) ((unsigned long) millis() % (long) 10)) - 5);
  4101. if ( radius<0.0 )
  4102. radius = -radius;
  4103. X_current = X_probe_location + cos(theta) * radius;
  4104. Y_current = Y_probe_location + sin(theta) * radius;
  4105. if ( X_current<X_MIN_POS) // Make sure our X & Y are sane
  4106. X_current = X_MIN_POS;
  4107. if ( X_current>X_MAX_POS)
  4108. X_current = X_MAX_POS;
  4109. if ( Y_current<Y_MIN_POS) // Make sure our X & Y are sane
  4110. Y_current = Y_MIN_POS;
  4111. if ( Y_current>Y_MAX_POS)
  4112. Y_current = Y_MAX_POS;
  4113. if (verbose_level>3 ) {
  4114. SERIAL_ECHOPAIR("x: ", X_current);
  4115. SERIAL_ECHOPAIR("y: ", Y_current);
  4116. SERIAL_PROTOCOLLNPGM("");
  4117. }
  4118. do_blocking_move_to( X_current, Y_current, Z_current );
  4119. }
  4120. do_blocking_move_to( X_probe_location, Y_probe_location, Z_start_location); // Go back to the probe location
  4121. }
  4122. setup_for_endstop_move();
  4123. run_z_probe();
  4124. sample_set[n] = current_position[Z_AXIS];
  4125. //
  4126. // Get the current mean for the data points we have so far
  4127. //
  4128. sum=0.0;
  4129. for( j=0; j<=n; j++) {
  4130. sum = sum + sample_set[j];
  4131. }
  4132. mean = sum / (double (n+1));
  4133. //
  4134. // Now, use that mean to calculate the standard deviation for the
  4135. // data points we have so far
  4136. //
  4137. sum=0.0;
  4138. for( j=0; j<=n; j++) {
  4139. sum = sum + (sample_set[j]-mean) * (sample_set[j]-mean);
  4140. }
  4141. sigma = sqrt( sum / (double (n+1)) );
  4142. if (verbose_level > 1) {
  4143. SERIAL_PROTOCOL(n+1);
  4144. SERIAL_PROTOCOL(" of ");
  4145. SERIAL_PROTOCOL(n_samples);
  4146. SERIAL_PROTOCOLPGM(" z: ");
  4147. SERIAL_PROTOCOL_F(current_position[Z_AXIS], 6);
  4148. }
  4149. if (verbose_level > 2) {
  4150. SERIAL_PROTOCOL(" mean: ");
  4151. SERIAL_PROTOCOL_F(mean,6);
  4152. SERIAL_PROTOCOL(" sigma: ");
  4153. SERIAL_PROTOCOL_F(sigma,6);
  4154. }
  4155. if (verbose_level > 0)
  4156. SERIAL_PROTOCOLPGM("\n");
  4157. plan_buffer_line( X_probe_location, Y_probe_location, Z_start_location,
  4158. current_position[E_AXIS], homing_feedrate[Z_AXIS]/60, active_extruder);
  4159. st_synchronize();
  4160. }
  4161. delay(1000);
  4162. clean_up_after_endstop_move();
  4163. // enable_endstops(true);
  4164. if (verbose_level > 0) {
  4165. SERIAL_PROTOCOLPGM("Mean: ");
  4166. SERIAL_PROTOCOL_F(mean, 6);
  4167. SERIAL_PROTOCOLPGM("\n");
  4168. }
  4169. SERIAL_PROTOCOLPGM("Standard Deviation: ");
  4170. SERIAL_PROTOCOL_F(sigma, 6);
  4171. SERIAL_PROTOCOLPGM("\n\n");
  4172. Sigma_Exit:
  4173. break;
  4174. }
  4175. #endif // Z_PROBE_REPEATABILITY_TEST
  4176. #endif // ENABLE_AUTO_BED_LEVELING
  4177. case 104: // M104
  4178. if(setTargetedHotend(104)){
  4179. break;
  4180. }
  4181. if (code_seen('S')) setTargetHotend(code_value(), tmp_extruder);
  4182. setWatch();
  4183. break;
  4184. case 112: // M112 -Emergency Stop
  4185. kill("", 3);
  4186. break;
  4187. case 140: // M140 set bed temp
  4188. if (code_seen('S')) setTargetBed(code_value());
  4189. break;
  4190. case 105 : // M105
  4191. if(setTargetedHotend(105)){
  4192. break;
  4193. }
  4194. #if defined(TEMP_0_PIN) && TEMP_0_PIN > -1
  4195. SERIAL_PROTOCOLPGM("ok T:");
  4196. SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
  4197. SERIAL_PROTOCOLPGM(" /");
  4198. SERIAL_PROTOCOL_F(degTargetHotend(tmp_extruder),1);
  4199. #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
  4200. SERIAL_PROTOCOLPGM(" B:");
  4201. SERIAL_PROTOCOL_F(degBed(),1);
  4202. SERIAL_PROTOCOLPGM(" /");
  4203. SERIAL_PROTOCOL_F(degTargetBed(),1);
  4204. #endif //TEMP_BED_PIN
  4205. for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
  4206. SERIAL_PROTOCOLPGM(" T");
  4207. SERIAL_PROTOCOL(cur_extruder);
  4208. SERIAL_PROTOCOLPGM(":");
  4209. SERIAL_PROTOCOL_F(degHotend(cur_extruder),1);
  4210. SERIAL_PROTOCOLPGM(" /");
  4211. SERIAL_PROTOCOL_F(degTargetHotend(cur_extruder),1);
  4212. }
  4213. #else
  4214. SERIAL_ERROR_START;
  4215. SERIAL_ERRORLNRPGM(_i("No thermistors - no temperature"));////MSG_ERR_NO_THERMISTORS c=0 r=0
  4216. #endif
  4217. SERIAL_PROTOCOLPGM(" @:");
  4218. #ifdef EXTRUDER_WATTS
  4219. SERIAL_PROTOCOL((EXTRUDER_WATTS * getHeaterPower(tmp_extruder))/127);
  4220. SERIAL_PROTOCOLPGM("W");
  4221. #else
  4222. SERIAL_PROTOCOL(getHeaterPower(tmp_extruder));
  4223. #endif
  4224. SERIAL_PROTOCOLPGM(" B@:");
  4225. #ifdef BED_WATTS
  4226. SERIAL_PROTOCOL((BED_WATTS * getHeaterPower(-1))/127);
  4227. SERIAL_PROTOCOLPGM("W");
  4228. #else
  4229. SERIAL_PROTOCOL(getHeaterPower(-1));
  4230. #endif
  4231. #ifdef PINDA_THERMISTOR
  4232. SERIAL_PROTOCOLPGM(" P:");
  4233. SERIAL_PROTOCOL_F(current_temperature_pinda,1);
  4234. #endif //PINDA_THERMISTOR
  4235. #ifdef AMBIENT_THERMISTOR
  4236. SERIAL_PROTOCOLPGM(" A:");
  4237. SERIAL_PROTOCOL_F(current_temperature_ambient,1);
  4238. #endif //AMBIENT_THERMISTOR
  4239. #ifdef SHOW_TEMP_ADC_VALUES
  4240. {float raw = 0.0;
  4241. #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
  4242. SERIAL_PROTOCOLPGM(" ADC B:");
  4243. SERIAL_PROTOCOL_F(degBed(),1);
  4244. SERIAL_PROTOCOLPGM("C->");
  4245. raw = rawBedTemp();
  4246. SERIAL_PROTOCOL_F(raw/OVERSAMPLENR,5);
  4247. SERIAL_PROTOCOLPGM(" Rb->");
  4248. SERIAL_PROTOCOL_F(100 * (1 + (PtA * (raw/OVERSAMPLENR)) + (PtB * sq((raw/OVERSAMPLENR)))), 5);
  4249. SERIAL_PROTOCOLPGM(" Rxb->");
  4250. SERIAL_PROTOCOL_F(raw, 5);
  4251. #endif
  4252. for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
  4253. SERIAL_PROTOCOLPGM(" T");
  4254. SERIAL_PROTOCOL(cur_extruder);
  4255. SERIAL_PROTOCOLPGM(":");
  4256. SERIAL_PROTOCOL_F(degHotend(cur_extruder),1);
  4257. SERIAL_PROTOCOLPGM("C->");
  4258. raw = rawHotendTemp(cur_extruder);
  4259. SERIAL_PROTOCOL_F(raw/OVERSAMPLENR,5);
  4260. SERIAL_PROTOCOLPGM(" Rt");
  4261. SERIAL_PROTOCOL(cur_extruder);
  4262. SERIAL_PROTOCOLPGM("->");
  4263. SERIAL_PROTOCOL_F(100 * (1 + (PtA * (raw/OVERSAMPLENR)) + (PtB * sq((raw/OVERSAMPLENR)))), 5);
  4264. SERIAL_PROTOCOLPGM(" Rx");
  4265. SERIAL_PROTOCOL(cur_extruder);
  4266. SERIAL_PROTOCOLPGM("->");
  4267. SERIAL_PROTOCOL_F(raw, 5);
  4268. }}
  4269. #endif
  4270. SERIAL_PROTOCOLLN("");
  4271. KEEPALIVE_STATE(NOT_BUSY);
  4272. return;
  4273. break;
  4274. case 109:
  4275. {// M109 - Wait for extruder heater to reach target.
  4276. if(setTargetedHotend(109)){
  4277. break;
  4278. }
  4279. LCD_MESSAGERPGM(_T(MSG_HEATING));
  4280. heating_status = 1;
  4281. if (farm_mode) { prusa_statistics(1); };
  4282. #ifdef AUTOTEMP
  4283. autotemp_enabled=false;
  4284. #endif
  4285. if (code_seen('S')) {
  4286. setTargetHotend(code_value(), tmp_extruder);
  4287. CooldownNoWait = true;
  4288. } else if (code_seen('R')) {
  4289. setTargetHotend(code_value(), tmp_extruder);
  4290. CooldownNoWait = false;
  4291. }
  4292. #ifdef AUTOTEMP
  4293. if (code_seen('S')) autotemp_min=code_value();
  4294. if (code_seen('B')) autotemp_max=code_value();
  4295. if (code_seen('F'))
  4296. {
  4297. autotemp_factor=code_value();
  4298. autotemp_enabled=true;
  4299. }
  4300. #endif
  4301. setWatch();
  4302. codenum = millis();
  4303. /* See if we are heating up or cooling down */
  4304. target_direction = isHeatingHotend(tmp_extruder); // true if heating, false if cooling
  4305. KEEPALIVE_STATE(NOT_BUSY);
  4306. cancel_heatup = false;
  4307. wait_for_heater(codenum); //loops until target temperature is reached
  4308. LCD_MESSAGERPGM(_T(MSG_HEATING_COMPLETE));
  4309. KEEPALIVE_STATE(IN_HANDLER);
  4310. heating_status = 2;
  4311. if (farm_mode) { prusa_statistics(2); };
  4312. //starttime=millis();
  4313. previous_millis_cmd = millis();
  4314. }
  4315. break;
  4316. case 190: // M190 - Wait for bed heater to reach target.
  4317. #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
  4318. LCD_MESSAGERPGM(_T(MSG_BED_HEATING));
  4319. heating_status = 3;
  4320. if (farm_mode) { prusa_statistics(1); };
  4321. if (code_seen('S'))
  4322. {
  4323. setTargetBed(code_value());
  4324. CooldownNoWait = true;
  4325. }
  4326. else if (code_seen('R'))
  4327. {
  4328. setTargetBed(code_value());
  4329. CooldownNoWait = false;
  4330. }
  4331. codenum = millis();
  4332. cancel_heatup = false;
  4333. target_direction = isHeatingBed(); // true if heating, false if cooling
  4334. KEEPALIVE_STATE(NOT_BUSY);
  4335. while ( (target_direction)&&(!cancel_heatup) ? (isHeatingBed()) : (isCoolingBed()&&(CooldownNoWait==false)) )
  4336. {
  4337. if(( millis() - codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
  4338. {
  4339. if (!farm_mode) {
  4340. float tt = degHotend(active_extruder);
  4341. SERIAL_PROTOCOLPGM("T:");
  4342. SERIAL_PROTOCOL(tt);
  4343. SERIAL_PROTOCOLPGM(" E:");
  4344. SERIAL_PROTOCOL((int)active_extruder);
  4345. SERIAL_PROTOCOLPGM(" B:");
  4346. SERIAL_PROTOCOL_F(degBed(), 1);
  4347. SERIAL_PROTOCOLLN("");
  4348. }
  4349. codenum = millis();
  4350. }
  4351. manage_heater();
  4352. manage_inactivity();
  4353. lcd_update();
  4354. }
  4355. LCD_MESSAGERPGM(_T(MSG_BED_DONE));
  4356. KEEPALIVE_STATE(IN_HANDLER);
  4357. heating_status = 4;
  4358. previous_millis_cmd = millis();
  4359. #endif
  4360. break;
  4361. #if defined(FAN_PIN) && FAN_PIN > -1
  4362. case 106: //M106 Fan On
  4363. if (code_seen('S')){
  4364. fanSpeed=constrain(code_value(),0,255);
  4365. }
  4366. else {
  4367. fanSpeed=255;
  4368. }
  4369. break;
  4370. case 107: //M107 Fan Off
  4371. fanSpeed = 0;
  4372. break;
  4373. #endif //FAN_PIN
  4374. #if defined(PS_ON_PIN) && PS_ON_PIN > -1
  4375. case 80: // M80 - Turn on Power Supply
  4376. SET_OUTPUT(PS_ON_PIN); //GND
  4377. WRITE(PS_ON_PIN, PS_ON_AWAKE);
  4378. // If you have a switch on suicide pin, this is useful
  4379. // if you want to start another print with suicide feature after
  4380. // a print without suicide...
  4381. #if defined SUICIDE_PIN && SUICIDE_PIN > -1
  4382. SET_OUTPUT(SUICIDE_PIN);
  4383. WRITE(SUICIDE_PIN, HIGH);
  4384. #endif
  4385. #ifdef ULTIPANEL
  4386. powersupply = true;
  4387. LCD_MESSAGERPGM(_T(WELCOME_MSG));
  4388. lcd_update();
  4389. #endif
  4390. break;
  4391. #endif
  4392. case 81: // M81 - Turn off Power Supply
  4393. disable_heater();
  4394. st_synchronize();
  4395. disable_e0();
  4396. disable_e1();
  4397. disable_e2();
  4398. finishAndDisableSteppers();
  4399. fanSpeed = 0;
  4400. delay(1000); // Wait a little before to switch off
  4401. #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
  4402. st_synchronize();
  4403. suicide();
  4404. #elif defined(PS_ON_PIN) && PS_ON_PIN > -1
  4405. SET_OUTPUT(PS_ON_PIN);
  4406. WRITE(PS_ON_PIN, PS_ON_ASLEEP);
  4407. #endif
  4408. #ifdef ULTIPANEL
  4409. powersupply = false;
  4410. LCD_MESSAGERPGM(CAT4(CUSTOM_MENDEL_NAME,PSTR(" "),MSG_OFF,PSTR("."))); //!!
  4411. /*
  4412. MACHNAME = "Prusa i3"
  4413. MSGOFF = "Vypnuto"
  4414. "Prusai3"" ""vypnuto""."
  4415. "Prusa i3"" "_T(MSG_ALL)[lang_selected][50]"."
  4416. */
  4417. lcd_update();
  4418. #endif
  4419. break;
  4420. case 82:
  4421. axis_relative_modes[3] = false;
  4422. break;
  4423. case 83:
  4424. axis_relative_modes[3] = true;
  4425. break;
  4426. case 18: //compatibility
  4427. case 84: // M84
  4428. if(code_seen('S')){
  4429. stepper_inactive_time = code_value() * 1000;
  4430. }
  4431. else
  4432. {
  4433. 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])));
  4434. if(all_axis)
  4435. {
  4436. st_synchronize();
  4437. disable_e0();
  4438. disable_e1();
  4439. disable_e2();
  4440. finishAndDisableSteppers();
  4441. }
  4442. else
  4443. {
  4444. st_synchronize();
  4445. if (code_seen('X')) disable_x();
  4446. if (code_seen('Y')) disable_y();
  4447. if (code_seen('Z')) disable_z();
  4448. #if ((E0_ENABLE_PIN != X_ENABLE_PIN) && (E1_ENABLE_PIN != Y_ENABLE_PIN)) // Only enable on boards that have seperate ENABLE_PINS
  4449. if (code_seen('E')) {
  4450. disable_e0();
  4451. disable_e1();
  4452. disable_e2();
  4453. }
  4454. #endif
  4455. }
  4456. }
  4457. snmm_filaments_used = 0;
  4458. break;
  4459. case 85: // M85
  4460. if(code_seen('S')) {
  4461. max_inactive_time = code_value() * 1000;
  4462. }
  4463. break;
  4464. case 92: // M92
  4465. for(int8_t i=0; i < NUM_AXIS; i++)
  4466. {
  4467. if(code_seen(axis_codes[i]))
  4468. {
  4469. if(i == 3) { // E
  4470. float value = code_value();
  4471. if(value < 20.0) {
  4472. float factor = axis_steps_per_unit[i] / value; // increase e constants if M92 E14 is given for netfab.
  4473. max_jerk[E_AXIS] *= factor;
  4474. max_feedrate[i] *= factor;
  4475. axis_steps_per_sqr_second[i] *= factor;
  4476. }
  4477. axis_steps_per_unit[i] = value;
  4478. }
  4479. else {
  4480. axis_steps_per_unit[i] = code_value();
  4481. }
  4482. }
  4483. }
  4484. break;
  4485. case 110: // M110 - reset line pos
  4486. if (code_seen('N'))
  4487. gcode_LastN = code_value_long();
  4488. break;
  4489. #ifdef HOST_KEEPALIVE_FEATURE
  4490. case 113: // M113 - Get or set Host Keepalive interval
  4491. if (code_seen('S')) {
  4492. host_keepalive_interval = (uint8_t)code_value_short();
  4493. // NOMORE(host_keepalive_interval, 60);
  4494. }
  4495. else {
  4496. SERIAL_ECHO_START;
  4497. SERIAL_ECHOPAIR("M113 S", (unsigned long)host_keepalive_interval);
  4498. SERIAL_PROTOCOLLN("");
  4499. }
  4500. break;
  4501. #endif
  4502. case 115: // M115
  4503. if (code_seen('V')) {
  4504. // Report the Prusa version number.
  4505. SERIAL_PROTOCOLLNRPGM(FW_VERSION_STR_P());
  4506. } else if (code_seen('U')) {
  4507. // Check the firmware version provided. If the firmware version provided by the U code is higher than the currently running firmware,
  4508. // pause the print and ask the user to upgrade the firmware.
  4509. show_upgrade_dialog_if_version_newer(++ strchr_pointer);
  4510. } else {
  4511. SERIAL_ECHOPGM("FIRMWARE_NAME:Prusa-Firmware ");
  4512. SERIAL_ECHORPGM(FW_VERSION_STR_P());
  4513. SERIAL_ECHOPGM(" based on Marlin FIRMWARE_URL:https://github.com/prusa3d/Prusa-Firmware PROTOCOL_VERSION:");
  4514. SERIAL_ECHOPGM(PROTOCOL_VERSION);
  4515. SERIAL_ECHOPGM(" MACHINE_TYPE:");
  4516. SERIAL_ECHOPGM(CUSTOM_MENDEL_NAME);
  4517. SERIAL_ECHOPGM(" EXTRUDER_COUNT:");
  4518. SERIAL_ECHOPGM(STRINGIFY(EXTRUDERS));
  4519. SERIAL_ECHOPGM(" UUID:");
  4520. SERIAL_ECHOLNPGM(MACHINE_UUID);
  4521. }
  4522. break;
  4523. /* case 117: // M117 display message
  4524. starpos = (strchr(strchr_pointer + 5,'*'));
  4525. if(starpos!=NULL)
  4526. *(starpos)='\0';
  4527. lcd_setstatus(strchr_pointer + 5);
  4528. break;*/
  4529. case 114: // M114
  4530. gcode_M114();
  4531. break;
  4532. case 120: // M120
  4533. enable_endstops(false) ;
  4534. break;
  4535. case 121: // M121
  4536. enable_endstops(true) ;
  4537. break;
  4538. case 119: // M119
  4539. SERIAL_PROTOCOLRPGM(_i("Reporting endstop status"));////MSG_M119_REPORT c=0 r=0
  4540. SERIAL_PROTOCOLLN("");
  4541. #if defined(X_MIN_PIN) && X_MIN_PIN > -1
  4542. SERIAL_PROTOCOLRPGM(_n("x_min: "));////MSG_X_MIN c=0 r=0
  4543. if(READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING){
  4544. SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_HIT));
  4545. }else{
  4546. SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_OPEN));
  4547. }
  4548. SERIAL_PROTOCOLLN("");
  4549. #endif
  4550. #if defined(X_MAX_PIN) && X_MAX_PIN > -1
  4551. SERIAL_PROTOCOLRPGM(_n("x_max: "));////MSG_X_MAX c=0 r=0
  4552. if(READ(X_MAX_PIN)^X_MAX_ENDSTOP_INVERTING){
  4553. SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_HIT));
  4554. }else{
  4555. SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_OPEN));
  4556. }
  4557. SERIAL_PROTOCOLLN("");
  4558. #endif
  4559. #if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
  4560. SERIAL_PROTOCOLRPGM(_n("y_min: "));////MSG_Y_MIN c=0 r=0
  4561. if(READ(Y_MIN_PIN)^Y_MIN_ENDSTOP_INVERTING){
  4562. SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_HIT));
  4563. }else{
  4564. SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_OPEN));
  4565. }
  4566. SERIAL_PROTOCOLLN("");
  4567. #endif
  4568. #if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
  4569. SERIAL_PROTOCOLRPGM(_n("y_max: "));////MSG_Y_MAX c=0 r=0
  4570. if(READ(Y_MAX_PIN)^Y_MAX_ENDSTOP_INVERTING){
  4571. SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_HIT));
  4572. }else{
  4573. SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_OPEN));
  4574. }
  4575. SERIAL_PROTOCOLLN("");
  4576. #endif
  4577. #if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
  4578. SERIAL_PROTOCOLRPGM(MSG_Z_MIN);
  4579. if(READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING){
  4580. SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_HIT));
  4581. }else{
  4582. SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_OPEN));
  4583. }
  4584. SERIAL_PROTOCOLLN("");
  4585. #endif
  4586. #if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
  4587. SERIAL_PROTOCOLRPGM(MSG_Z_MAX);
  4588. if(READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING){
  4589. SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_HIT));
  4590. }else{
  4591. SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_OPEN));
  4592. }
  4593. SERIAL_PROTOCOLLN("");
  4594. #endif
  4595. break;
  4596. //TODO: update for all axis, use for loop
  4597. #ifdef BLINKM
  4598. case 150: // M150
  4599. {
  4600. byte red;
  4601. byte grn;
  4602. byte blu;
  4603. if(code_seen('R')) red = code_value();
  4604. if(code_seen('U')) grn = code_value();
  4605. if(code_seen('B')) blu = code_value();
  4606. SendColors(red,grn,blu);
  4607. }
  4608. break;
  4609. #endif //BLINKM
  4610. case 200: // M200 D<millimeters> set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).
  4611. {
  4612. tmp_extruder = active_extruder;
  4613. if(code_seen('T')) {
  4614. tmp_extruder = code_value();
  4615. if(tmp_extruder >= EXTRUDERS) {
  4616. SERIAL_ECHO_START;
  4617. SERIAL_ECHO(_i("M200 Invalid extruder "));////MSG_M200_INVALID_EXTRUDER c=0 r=0
  4618. break;
  4619. }
  4620. }
  4621. float area = .0;
  4622. if(code_seen('D')) {
  4623. float diameter = (float)code_value();
  4624. if (diameter == 0.0) {
  4625. // setting any extruder filament size disables volumetric on the assumption that
  4626. // slicers either generate in extruder values as cubic mm or as as filament feeds
  4627. // for all extruders
  4628. volumetric_enabled = false;
  4629. } else {
  4630. filament_size[tmp_extruder] = (float)code_value();
  4631. // make sure all extruders have some sane value for the filament size
  4632. filament_size[0] = (filament_size[0] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[0]);
  4633. #if EXTRUDERS > 1
  4634. filament_size[1] = (filament_size[1] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[1]);
  4635. #if EXTRUDERS > 2
  4636. filament_size[2] = (filament_size[2] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[2]);
  4637. #endif
  4638. #endif
  4639. volumetric_enabled = true;
  4640. }
  4641. } else {
  4642. //reserved for setting filament diameter via UFID or filament measuring device
  4643. break;
  4644. }
  4645. calculate_extruder_multipliers();
  4646. }
  4647. break;
  4648. case 201: // M201
  4649. for(int8_t i=0; i < NUM_AXIS; i++)
  4650. {
  4651. if(code_seen(axis_codes[i]))
  4652. {
  4653. max_acceleration_units_per_sq_second[i] = code_value();
  4654. }
  4655. }
  4656. // 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)
  4657. reset_acceleration_rates();
  4658. break;
  4659. #if 0 // Not used for Sprinter/grbl gen6
  4660. case 202: // M202
  4661. for(int8_t i=0; i < NUM_AXIS; i++) {
  4662. if(code_seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i];
  4663. }
  4664. break;
  4665. #endif
  4666. case 203: // M203 max feedrate mm/sec
  4667. for(int8_t i=0; i < NUM_AXIS; i++) {
  4668. if(code_seen(axis_codes[i])) max_feedrate[i] = code_value();
  4669. }
  4670. break;
  4671. case 204: // M204 acclereration S normal moves T filmanent only moves
  4672. {
  4673. if(code_seen('S')) acceleration = code_value() ;
  4674. if(code_seen('T')) retract_acceleration = code_value() ;
  4675. }
  4676. break;
  4677. 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
  4678. {
  4679. if(code_seen('S')) minimumfeedrate = code_value();
  4680. if(code_seen('T')) mintravelfeedrate = code_value();
  4681. if(code_seen('B')) minsegmenttime = code_value() ;
  4682. if(code_seen('X')) max_jerk[X_AXIS] = max_jerk[Y_AXIS] = code_value();
  4683. if(code_seen('Y')) max_jerk[Y_AXIS] = code_value();
  4684. if(code_seen('Z')) max_jerk[Z_AXIS] = code_value();
  4685. if(code_seen('E')) max_jerk[E_AXIS] = code_value();
  4686. if (max_jerk[X_AXIS] > DEFAULT_XJERK) max_jerk[X_AXIS] = DEFAULT_XJERK;
  4687. if (max_jerk[Y_AXIS] > DEFAULT_YJERK) max_jerk[Y_AXIS] = DEFAULT_YJERK;
  4688. }
  4689. break;
  4690. case 206: // M206 additional homing offset
  4691. for(int8_t i=0; i < 3; i++)
  4692. {
  4693. if(code_seen(axis_codes[i])) add_homing[i] = code_value();
  4694. }
  4695. break;
  4696. #ifdef FWRETRACT
  4697. case 207: //M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop]
  4698. {
  4699. if(code_seen('S'))
  4700. {
  4701. retract_length = code_value() ;
  4702. }
  4703. if(code_seen('F'))
  4704. {
  4705. retract_feedrate = code_value()/60 ;
  4706. }
  4707. if(code_seen('Z'))
  4708. {
  4709. retract_zlift = code_value() ;
  4710. }
  4711. }break;
  4712. case 208: // M208 - set retract recover length S[positive mm surplus to the M207 S*] F[feedrate mm/min]
  4713. {
  4714. if(code_seen('S'))
  4715. {
  4716. retract_recover_length = code_value() ;
  4717. }
  4718. if(code_seen('F'))
  4719. {
  4720. retract_recover_feedrate = code_value()/60 ;
  4721. }
  4722. }break;
  4723. 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.
  4724. {
  4725. if(code_seen('S'))
  4726. {
  4727. int t= code_value() ;
  4728. switch(t)
  4729. {
  4730. case 0:
  4731. {
  4732. autoretract_enabled=false;
  4733. retracted[0]=false;
  4734. #if EXTRUDERS > 1
  4735. retracted[1]=false;
  4736. #endif
  4737. #if EXTRUDERS > 2
  4738. retracted[2]=false;
  4739. #endif
  4740. }break;
  4741. case 1:
  4742. {
  4743. autoretract_enabled=true;
  4744. retracted[0]=false;
  4745. #if EXTRUDERS > 1
  4746. retracted[1]=false;
  4747. #endif
  4748. #if EXTRUDERS > 2
  4749. retracted[2]=false;
  4750. #endif
  4751. }break;
  4752. default:
  4753. SERIAL_ECHO_START;
  4754. SERIAL_ECHORPGM(MSG_UNKNOWN_COMMAND);
  4755. SERIAL_ECHO(CMDBUFFER_CURRENT_STRING);
  4756. SERIAL_ECHOLNPGM("\"(1)");
  4757. }
  4758. }
  4759. }break;
  4760. #endif // FWRETRACT
  4761. #if EXTRUDERS > 1
  4762. case 218: // M218 - set hotend offset (in mm), T<extruder_number> X<offset_on_X> Y<offset_on_Y>
  4763. {
  4764. if(setTargetedHotend(218)){
  4765. break;
  4766. }
  4767. if(code_seen('X'))
  4768. {
  4769. extruder_offset[X_AXIS][tmp_extruder] = code_value();
  4770. }
  4771. if(code_seen('Y'))
  4772. {
  4773. extruder_offset[Y_AXIS][tmp_extruder] = code_value();
  4774. }
  4775. SERIAL_ECHO_START;
  4776. SERIAL_ECHORPGM(MSG_HOTEND_OFFSET);
  4777. for(tmp_extruder = 0; tmp_extruder < EXTRUDERS; tmp_extruder++)
  4778. {
  4779. SERIAL_ECHO(" ");
  4780. SERIAL_ECHO(extruder_offset[X_AXIS][tmp_extruder]);
  4781. SERIAL_ECHO(",");
  4782. SERIAL_ECHO(extruder_offset[Y_AXIS][tmp_extruder]);
  4783. }
  4784. SERIAL_ECHOLN("");
  4785. }break;
  4786. #endif
  4787. case 220: // M220 S<factor in percent>- set speed factor override percentage
  4788. {
  4789. if(code_seen('S'))
  4790. {
  4791. feedmultiply = code_value() ;
  4792. }
  4793. }
  4794. break;
  4795. case 221: // M221 S<factor in percent>- set extrude factor override percentage
  4796. {
  4797. if(code_seen('S'))
  4798. {
  4799. int tmp_code = code_value();
  4800. if (code_seen('T'))
  4801. {
  4802. if(setTargetedHotend(221)){
  4803. break;
  4804. }
  4805. extruder_multiply[tmp_extruder] = tmp_code;
  4806. }
  4807. else
  4808. {
  4809. extrudemultiply = tmp_code ;
  4810. }
  4811. }
  4812. calculate_extruder_multipliers();
  4813. }
  4814. break;
  4815. #ifndef _DISABLE_M42_M226
  4816. case 226: // M226 P<pin number> S<pin state>- Wait until the specified pin reaches the state required
  4817. {
  4818. if(code_seen('P')){
  4819. int pin_number = code_value(); // pin number
  4820. int pin_state = -1; // required pin state - default is inverted
  4821. if(code_seen('S')) pin_state = code_value(); // required pin state
  4822. if(pin_state >= -1 && pin_state <= 1){
  4823. for(int8_t i = 0; i < (int8_t)(sizeof(sensitive_pins)/sizeof(int)); i++)
  4824. {
  4825. if (sensitive_pins[i] == pin_number)
  4826. {
  4827. pin_number = -1;
  4828. break;
  4829. }
  4830. }
  4831. if (pin_number > -1)
  4832. {
  4833. int target = LOW;
  4834. st_synchronize();
  4835. pinMode(pin_number, INPUT);
  4836. switch(pin_state){
  4837. case 1:
  4838. target = HIGH;
  4839. break;
  4840. case 0:
  4841. target = LOW;
  4842. break;
  4843. case -1:
  4844. target = !digitalRead(pin_number);
  4845. break;
  4846. }
  4847. while(digitalRead(pin_number) != target){
  4848. manage_heater();
  4849. manage_inactivity();
  4850. lcd_update();
  4851. }
  4852. }
  4853. }
  4854. }
  4855. }
  4856. break;
  4857. #endif //_DISABLE_M42_M226
  4858. #if NUM_SERVOS > 0
  4859. case 280: // M280 - set servo position absolute. P: servo index, S: angle or microseconds
  4860. {
  4861. int servo_index = -1;
  4862. int servo_position = 0;
  4863. if (code_seen('P'))
  4864. servo_index = code_value();
  4865. if (code_seen('S')) {
  4866. servo_position = code_value();
  4867. if ((servo_index >= 0) && (servo_index < NUM_SERVOS)) {
  4868. #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
  4869. servos[servo_index].attach(0);
  4870. #endif
  4871. servos[servo_index].write(servo_position);
  4872. #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
  4873. delay(PROBE_SERVO_DEACTIVATION_DELAY);
  4874. servos[servo_index].detach();
  4875. #endif
  4876. }
  4877. else {
  4878. SERIAL_ECHO_START;
  4879. SERIAL_ECHO("Servo ");
  4880. SERIAL_ECHO(servo_index);
  4881. SERIAL_ECHOLN(" out of range");
  4882. }
  4883. }
  4884. else if (servo_index >= 0) {
  4885. SERIAL_PROTOCOL(_T(MSG_OK));
  4886. SERIAL_PROTOCOL(" Servo ");
  4887. SERIAL_PROTOCOL(servo_index);
  4888. SERIAL_PROTOCOL(": ");
  4889. SERIAL_PROTOCOL(servos[servo_index].read());
  4890. SERIAL_PROTOCOLLN("");
  4891. }
  4892. }
  4893. break;
  4894. #endif // NUM_SERVOS > 0
  4895. #if (LARGE_FLASH == true && ( BEEPER > 0 || defined(ULTRALCD) || defined(LCD_USE_I2C_BUZZER)))
  4896. case 300: // M300
  4897. {
  4898. int beepS = code_seen('S') ? code_value() : 110;
  4899. int beepP = code_seen('P') ? code_value() : 1000;
  4900. if (beepS > 0)
  4901. {
  4902. #if BEEPER > 0
  4903. tone(BEEPER, beepS);
  4904. delay(beepP);
  4905. noTone(BEEPER);
  4906. #elif defined(ULTRALCD)
  4907. lcd_buzz(beepS, beepP);
  4908. #elif defined(LCD_USE_I2C_BUZZER)
  4909. lcd_buzz(beepP, beepS);
  4910. #endif
  4911. }
  4912. else
  4913. {
  4914. delay(beepP);
  4915. }
  4916. }
  4917. break;
  4918. #endif // M300
  4919. #ifdef PIDTEMP
  4920. case 301: // M301
  4921. {
  4922. if(code_seen('P')) Kp = code_value();
  4923. if(code_seen('I')) Ki = scalePID_i(code_value());
  4924. if(code_seen('D')) Kd = scalePID_d(code_value());
  4925. #ifdef PID_ADD_EXTRUSION_RATE
  4926. if(code_seen('C')) Kc = code_value();
  4927. #endif
  4928. updatePID();
  4929. SERIAL_PROTOCOLRPGM(_T(MSG_OK));
  4930. SERIAL_PROTOCOL(" p:");
  4931. SERIAL_PROTOCOL(Kp);
  4932. SERIAL_PROTOCOL(" i:");
  4933. SERIAL_PROTOCOL(unscalePID_i(Ki));
  4934. SERIAL_PROTOCOL(" d:");
  4935. SERIAL_PROTOCOL(unscalePID_d(Kd));
  4936. #ifdef PID_ADD_EXTRUSION_RATE
  4937. SERIAL_PROTOCOL(" c:");
  4938. //Kc does not have scaling applied above, or in resetting defaults
  4939. SERIAL_PROTOCOL(Kc);
  4940. #endif
  4941. SERIAL_PROTOCOLLN("");
  4942. }
  4943. break;
  4944. #endif //PIDTEMP
  4945. #ifdef PIDTEMPBED
  4946. case 304: // M304
  4947. {
  4948. if(code_seen('P')) bedKp = code_value();
  4949. if(code_seen('I')) bedKi = scalePID_i(code_value());
  4950. if(code_seen('D')) bedKd = scalePID_d(code_value());
  4951. updatePID();
  4952. SERIAL_PROTOCOLRPGM(_T(MSG_OK));
  4953. SERIAL_PROTOCOL(" p:");
  4954. SERIAL_PROTOCOL(bedKp);
  4955. SERIAL_PROTOCOL(" i:");
  4956. SERIAL_PROTOCOL(unscalePID_i(bedKi));
  4957. SERIAL_PROTOCOL(" d:");
  4958. SERIAL_PROTOCOL(unscalePID_d(bedKd));
  4959. SERIAL_PROTOCOLLN("");
  4960. }
  4961. break;
  4962. #endif //PIDTEMP
  4963. case 240: // M240 Triggers a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/
  4964. {
  4965. #ifdef CHDK
  4966. SET_OUTPUT(CHDK);
  4967. WRITE(CHDK, HIGH);
  4968. chdkHigh = millis();
  4969. chdkActive = true;
  4970. #else
  4971. #if defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1
  4972. const uint8_t NUM_PULSES=16;
  4973. const float PULSE_LENGTH=0.01524;
  4974. for(int i=0; i < NUM_PULSES; i++) {
  4975. WRITE(PHOTOGRAPH_PIN, HIGH);
  4976. _delay_ms(PULSE_LENGTH);
  4977. WRITE(PHOTOGRAPH_PIN, LOW);
  4978. _delay_ms(PULSE_LENGTH);
  4979. }
  4980. delay(7.33);
  4981. for(int i=0; i < NUM_PULSES; i++) {
  4982. WRITE(PHOTOGRAPH_PIN, HIGH);
  4983. _delay_ms(PULSE_LENGTH);
  4984. WRITE(PHOTOGRAPH_PIN, LOW);
  4985. _delay_ms(PULSE_LENGTH);
  4986. }
  4987. #endif
  4988. #endif //chdk end if
  4989. }
  4990. break;
  4991. #ifdef DOGLCD
  4992. case 250: // M250 Set LCD contrast value: C<value> (value 0..63)
  4993. {
  4994. if (code_seen('C')) {
  4995. lcd_setcontrast( ((int)code_value())&63 );
  4996. }
  4997. SERIAL_PROTOCOLPGM("lcd contrast value: ");
  4998. SERIAL_PROTOCOL(lcd_contrast);
  4999. SERIAL_PROTOCOLLN("");
  5000. }
  5001. break;
  5002. #endif
  5003. #ifdef PREVENT_DANGEROUS_EXTRUDE
  5004. case 302: // allow cold extrudes, or set the minimum extrude temperature
  5005. {
  5006. float temp = .0;
  5007. if (code_seen('S')) temp=code_value();
  5008. set_extrude_min_temp(temp);
  5009. }
  5010. break;
  5011. #endif
  5012. case 303: // M303 PID autotune
  5013. {
  5014. float temp = 150.0;
  5015. int e=0;
  5016. int c=5;
  5017. if (code_seen('E')) e=code_value();
  5018. if (e<0)
  5019. temp=70;
  5020. if (code_seen('S')) temp=code_value();
  5021. if (code_seen('C')) c=code_value();
  5022. PID_autotune(temp, e, c);
  5023. }
  5024. break;
  5025. case 400: // M400 finish all moves
  5026. {
  5027. st_synchronize();
  5028. }
  5029. break;
  5030. case 500: // M500 Store settings in EEPROM
  5031. {
  5032. Config_StoreSettings(EEPROM_OFFSET);
  5033. }
  5034. break;
  5035. case 501: // M501 Read settings from EEPROM
  5036. {
  5037. Config_RetrieveSettings(EEPROM_OFFSET);
  5038. }
  5039. break;
  5040. case 502: // M502 Revert to default settings
  5041. {
  5042. Config_ResetDefault();
  5043. }
  5044. break;
  5045. case 503: // M503 print settings currently in memory
  5046. {
  5047. Config_PrintSettings();
  5048. }
  5049. break;
  5050. case 509: //M509 Force language selection
  5051. {
  5052. lcd_force_language_selection();
  5053. SERIAL_ECHO_START;
  5054. SERIAL_PROTOCOLPGM(("LANG SEL FORCED"));
  5055. }
  5056. break;
  5057. #ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
  5058. case 540:
  5059. {
  5060. if(code_seen('S')) abort_on_endstop_hit = code_value() > 0;
  5061. }
  5062. break;
  5063. #endif
  5064. #ifdef CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
  5065. case CUSTOM_M_CODE_SET_Z_PROBE_OFFSET:
  5066. {
  5067. float value;
  5068. if (code_seen('Z'))
  5069. {
  5070. value = code_value();
  5071. if ((Z_PROBE_OFFSET_RANGE_MIN <= value) && (value <= Z_PROBE_OFFSET_RANGE_MAX))
  5072. {
  5073. zprobe_zoffset = -value; // compare w/ line 278 of ConfigurationStore.cpp
  5074. SERIAL_ECHO_START;
  5075. SERIAL_ECHOLNRPGM(CAT4(MSG_ZPROBE_ZOFFSET, " ", _T(MSG_OK),PSTR("")));
  5076. SERIAL_PROTOCOLLN("");
  5077. }
  5078. else
  5079. {
  5080. SERIAL_ECHO_START;
  5081. SERIAL_ECHORPGM(MSG_ZPROBE_ZOFFSET);
  5082. SERIAL_ECHORPGM(MSG_Z_MIN);
  5083. SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MIN);
  5084. SERIAL_ECHORPGM(MSG_Z_MAX);
  5085. SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MAX);
  5086. SERIAL_PROTOCOLLN("");
  5087. }
  5088. }
  5089. else
  5090. {
  5091. SERIAL_ECHO_START;
  5092. SERIAL_ECHOLNRPGM(CAT2(MSG_ZPROBE_ZOFFSET, PSTR(" : ")));
  5093. SERIAL_ECHO(-zprobe_zoffset);
  5094. SERIAL_PROTOCOLLN("");
  5095. }
  5096. break;
  5097. }
  5098. #endif // CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
  5099. #ifdef FILAMENTCHANGEENABLE
  5100. case 600: //Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
  5101. {
  5102. #ifdef PAT9125
  5103. bool old_fsensor_enabled = fsensor_enabled;
  5104. fsensor_enabled = false; //temporary solution for unexpected restarting
  5105. #endif //PAT9125
  5106. st_synchronize();
  5107. float target[4];
  5108. float lastpos[4];
  5109. if (farm_mode)
  5110. {
  5111. prusa_statistics(22);
  5112. }
  5113. feedmultiplyBckp=feedmultiply;
  5114. int8_t TooLowZ = 0;
  5115. float HotendTempBckp = degTargetHotend(active_extruder);
  5116. int fanSpeedBckp = fanSpeed;
  5117. target[X_AXIS]=current_position[X_AXIS];
  5118. target[Y_AXIS]=current_position[Y_AXIS];
  5119. target[Z_AXIS]=current_position[Z_AXIS];
  5120. target[E_AXIS]=current_position[E_AXIS];
  5121. lastpos[X_AXIS]=current_position[X_AXIS];
  5122. lastpos[Y_AXIS]=current_position[Y_AXIS];
  5123. lastpos[Z_AXIS]=current_position[Z_AXIS];
  5124. lastpos[E_AXIS]=current_position[E_AXIS];
  5125. //Restract extruder
  5126. if(code_seen('E'))
  5127. {
  5128. target[E_AXIS]+= code_value();
  5129. }
  5130. else
  5131. {
  5132. #ifdef FILAMENTCHANGE_FIRSTRETRACT
  5133. target[E_AXIS]+= FILAMENTCHANGE_FIRSTRETRACT ;
  5134. #endif
  5135. }
  5136. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder);
  5137. //Lift Z
  5138. if(code_seen('Z'))
  5139. {
  5140. target[Z_AXIS]+= code_value();
  5141. }
  5142. else
  5143. {
  5144. #ifdef FILAMENTCHANGE_ZADD
  5145. target[Z_AXIS]+= FILAMENTCHANGE_ZADD ;
  5146. if(target[Z_AXIS] < 10){
  5147. target[Z_AXIS]+= 10 ;
  5148. TooLowZ = 1;
  5149. }else{
  5150. TooLowZ = 0;
  5151. }
  5152. #endif
  5153. }
  5154. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_ZFEED, active_extruder);
  5155. //Move XY to side
  5156. if(code_seen('X'))
  5157. {
  5158. target[X_AXIS]+= code_value();
  5159. }
  5160. else
  5161. {
  5162. #ifdef FILAMENTCHANGE_XPOS
  5163. target[X_AXIS]= FILAMENTCHANGE_XPOS ;
  5164. #endif
  5165. }
  5166. if(code_seen('Y'))
  5167. {
  5168. target[Y_AXIS]= code_value();
  5169. }
  5170. else
  5171. {
  5172. #ifdef FILAMENTCHANGE_YPOS
  5173. target[Y_AXIS]= FILAMENTCHANGE_YPOS ;
  5174. #endif
  5175. }
  5176. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_XYFEED, active_extruder);
  5177. st_synchronize();
  5178. KEEPALIVE_STATE(PAUSED_FOR_USER);
  5179. uint8_t cnt = 0;
  5180. int counterBeep = 0;
  5181. fanSpeed = 0;
  5182. unsigned long waiting_start_time = millis();
  5183. uint8_t wait_for_user_state = 0;
  5184. lcd_display_message_fullscreen_P(_T(MSG_PRESS_TO_UNLOAD));
  5185. while (!(wait_for_user_state == 0 && lcd_clicked())){
  5186. //cnt++;
  5187. manage_heater();
  5188. manage_inactivity(true);
  5189. /*#ifdef SNMM
  5190. target[E_AXIS] += 0.002;
  5191. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 500, active_extruder);
  5192. #endif // SNMM*/
  5193. //if (cnt == 0)
  5194. {
  5195. #if BEEPER > 0
  5196. if (counterBeep == 500) {
  5197. counterBeep = 0;
  5198. }
  5199. SET_OUTPUT(BEEPER);
  5200. if (counterBeep == 0) {
  5201. WRITE(BEEPER, HIGH);
  5202. }
  5203. if (counterBeep == 20) {
  5204. WRITE(BEEPER, LOW);
  5205. }
  5206. counterBeep++;
  5207. #else
  5208. #if !defined(LCD_FEEDBACK_FREQUENCY_HZ) || !defined(LCD_FEEDBACK_FREQUENCY_DURATION_MS)
  5209. lcd_buzz(1000 / 6, 100);
  5210. #else
  5211. lcd_buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ);
  5212. #endif
  5213. #endif
  5214. }
  5215. switch (wait_for_user_state) {
  5216. case 0:
  5217. delay_keep_alive(4);
  5218. if (millis() > waiting_start_time + (unsigned long)M600_TIMEOUT * 1000) {
  5219. lcd_display_message_fullscreen_P(_i("Press knob to preheat nozzle and continue."));////MSG_PRESS_TO_PREHEAT c=20 r=4
  5220. wait_for_user_state = 1;
  5221. setTargetHotend(0, 0);
  5222. setTargetHotend(0, 1);
  5223. setTargetHotend(0, 2);
  5224. st_synchronize();
  5225. disable_e0();
  5226. disable_e1();
  5227. disable_e2();
  5228. }
  5229. break;
  5230. case 1:
  5231. delay_keep_alive(4);
  5232. if (lcd_clicked()) {
  5233. setTargetHotend(HotendTempBckp, active_extruder);
  5234. lcd_wait_for_heater();
  5235. wait_for_user_state = 2;
  5236. }
  5237. break;
  5238. case 2:
  5239. if (abs(degTargetHotend(active_extruder) - degHotend(active_extruder)) < 1) {
  5240. lcd_display_message_fullscreen_P(_T(MSG_PRESS_TO_UNLOAD));
  5241. waiting_start_time = millis();
  5242. wait_for_user_state = 0;
  5243. }
  5244. else {
  5245. counterBeep = 20; //beeper will be inactive during waiting for nozzle preheat
  5246. lcd.setCursor(1, 4);
  5247. lcd.print(ftostr3(degHotend(active_extruder)));
  5248. }
  5249. break;
  5250. }
  5251. }
  5252. WRITE(BEEPER, LOW);
  5253. lcd_change_fil_state = 0;
  5254. // Unload filament
  5255. lcd_display_message_fullscreen_P(_T(MSG_UNLOADING_FILAMENT));
  5256. KEEPALIVE_STATE(IN_HANDLER);
  5257. custom_message = true;
  5258. lcd_setstatuspgm(_T(MSG_UNLOADING_FILAMENT));
  5259. if (code_seen('L'))
  5260. {
  5261. target[E_AXIS] += code_value();
  5262. }
  5263. else
  5264. {
  5265. #ifdef SNMM
  5266. #else
  5267. #ifdef FILAMENTCHANGE_FINALRETRACT
  5268. target[E_AXIS] += FILAMENTCHANGE_FINALRETRACT;
  5269. #endif
  5270. #endif // SNMM
  5271. }
  5272. #ifdef SNMM
  5273. target[E_AXIS] += 12;
  5274. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 3500, active_extruder);
  5275. target[E_AXIS] += 6;
  5276. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 5000, active_extruder);
  5277. target[E_AXIS] += (FIL_LOAD_LENGTH * -1);
  5278. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 5000, active_extruder);
  5279. st_synchronize();
  5280. target[E_AXIS] += (FIL_COOLING);
  5281. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 50, active_extruder);
  5282. target[E_AXIS] += (FIL_COOLING*-1);
  5283. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 50, active_extruder);
  5284. target[E_AXIS] += (bowden_length[snmm_extruder] * -1);
  5285. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 3000, active_extruder);
  5286. st_synchronize();
  5287. #else
  5288. // plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder);
  5289. //plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 3500 / 60, active_extruder);
  5290. target[E_AXIS] -= FILAMENTCHANGE_FINALRETRACT;
  5291. st_synchronize();
  5292. #ifdef TMC2130
  5293. uint8_t tmc2130_current_r_bckp = tmc2130_current_r[E_AXIS];
  5294. tmc2130_set_current_r(E_AXIS, TMC2130_UNLOAD_CURRENT_R);
  5295. #else
  5296. st_current_set(2, 200); //set lower E motor current for unload to protect filament sensor and ptfe tube
  5297. float tmp_motor[3] = DEFAULT_PWM_MOTOR_CURRENT;
  5298. float tmp_motor_loud[3] = DEFAULT_PWM_MOTOR_CURRENT_LOUD;
  5299. #endif //TMC2130
  5300. target[E_AXIS] -= 45;
  5301. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 5200 / 60, active_extruder);
  5302. st_synchronize();
  5303. target[E_AXIS] -= 15;
  5304. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 1000 / 60, active_extruder);
  5305. st_synchronize();
  5306. target[E_AXIS] -= 20;
  5307. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 1000 / 60, active_extruder);
  5308. st_synchronize();
  5309. #ifdef TMC2130
  5310. tmc2130_set_current_r(E_AXIS, tmc2130_current_r_bckp);
  5311. #else
  5312. uint8_t silentMode = eeprom_read_byte((uint8_t*)EEPROM_SILENT);
  5313. if(silentMode != SILENT_MODE_POWER) st_current_set(2, tmp_motor[2]); //set E back to normal operation currents
  5314. else st_current_set(2, tmp_motor_loud[2]);
  5315. #endif //TMC2130
  5316. #endif // SNMM
  5317. //finish moves
  5318. st_synchronize();
  5319. lcd_display_message_fullscreen_P(_T(MSG_PULL_OUT_FILAMENT));
  5320. //disable extruder steppers so filament can be removed
  5321. disable_e0();
  5322. disable_e1();
  5323. disable_e2();
  5324. delay(100);
  5325. WRITE(BEEPER, HIGH);
  5326. counterBeep = 0;
  5327. while(!lcd_clicked() && (counterBeep < 50)) {
  5328. if(counterBeep > 5) WRITE(BEEPER, LOW);
  5329. delay_keep_alive(100);
  5330. counterBeep++;
  5331. }
  5332. WRITE(BEEPER, LOW);
  5333. KEEPALIVE_STATE(PAUSED_FOR_USER);
  5334. lcd_change_fil_state = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Was filament unload successful?"), false, true);////MSG_UNLOAD_SUCCESSFUL c=20 r=2
  5335. if (lcd_change_fil_state == 0) lcd_show_fullscreen_message_and_wait_P(_i("Please open idler and remove filament manually."));////MSG_CHECK_IDLER c=20 r=4
  5336. //lcd_return_to_status();
  5337. lcd_update_enable(true);
  5338. //Wait for user to insert filament
  5339. lcd_wait_interact();
  5340. //load_filament_time = millis();
  5341. KEEPALIVE_STATE(PAUSED_FOR_USER);
  5342. #ifdef PAT9125
  5343. if (filament_autoload_enabled && (old_fsensor_enabled || fsensor_M600)) fsensor_autoload_check_start();
  5344. #endif //PAT9125
  5345. // printf_P(PSTR("M600 PAT9125 filament_autoload_enabled=%d, old_fsensor_enabled=%d, fsensor_M600=%d"), filament_autoload_enabled, old_fsensor_enabled, fsensor_M600);
  5346. while(!lcd_clicked())
  5347. {
  5348. manage_heater();
  5349. manage_inactivity(true);
  5350. #ifdef PAT9125
  5351. if (filament_autoload_enabled && (old_fsensor_enabled || fsensor_M600) && fsensor_check_autoload())
  5352. {
  5353. tone(BEEPER, 1000);
  5354. delay_keep_alive(50);
  5355. noTone(BEEPER);
  5356. break;
  5357. }
  5358. #endif //PAT9125
  5359. /*#ifdef SNMM
  5360. target[E_AXIS] += 0.002;
  5361. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 500, active_extruder);
  5362. #endif // SNMM*/
  5363. }
  5364. #ifdef PAT9125
  5365. if (filament_autoload_enabled && (old_fsensor_enabled || fsensor_M600)) fsensor_autoload_check_stop();
  5366. #endif //PAT9125
  5367. //WRITE(BEEPER, LOW);
  5368. KEEPALIVE_STATE(IN_HANDLER);
  5369. #ifdef SNMM
  5370. display_loading();
  5371. KEEPALIVE_STATE(PAUSED_FOR_USER);
  5372. do {
  5373. target[E_AXIS] += 0.002;
  5374. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 500, active_extruder);
  5375. delay_keep_alive(2);
  5376. } while (!lcd_clicked());
  5377. KEEPALIVE_STATE(IN_HANDLER);
  5378. /*if (millis() - load_filament_time > 2) {
  5379. load_filament_time = millis();
  5380. target[E_AXIS] += 0.001;
  5381. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 1000, active_extruder);
  5382. }*/
  5383. //Filament inserted
  5384. //Feed the filament to the end of nozzle quickly
  5385. st_synchronize();
  5386. target[E_AXIS] += bowden_length[snmm_extruder];
  5387. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 3000, active_extruder);
  5388. target[E_AXIS] += FIL_LOAD_LENGTH - 60;
  5389. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 1400, active_extruder);
  5390. target[E_AXIS] += 40;
  5391. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 400, active_extruder);
  5392. target[E_AXIS] += 10;
  5393. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 50, active_extruder);
  5394. #else
  5395. target[E_AXIS] += FILAMENTCHANGE_FIRSTFEED;
  5396. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EFEED, active_extruder);
  5397. #endif // SNMM
  5398. //Extrude some filament
  5399. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  5400. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EXFEED, active_extruder);
  5401. //Wait for user to check the state
  5402. lcd_change_fil_state = 0;
  5403. lcd_loading_filament();
  5404. tone(BEEPER, 500);
  5405. delay_keep_alive(50);
  5406. noTone(BEEPER);
  5407. while ((lcd_change_fil_state == 0)||(lcd_change_fil_state != 1)){
  5408. lcd_change_fil_state = 0;
  5409. KEEPALIVE_STATE(PAUSED_FOR_USER);
  5410. lcd_alright();
  5411. KEEPALIVE_STATE(IN_HANDLER);
  5412. switch(lcd_change_fil_state){
  5413. // Filament failed to load so load it again
  5414. case 2:
  5415. #ifdef SNMM
  5416. display_loading();
  5417. do {
  5418. target[E_AXIS] += 0.002;
  5419. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 500, active_extruder);
  5420. delay_keep_alive(2);
  5421. } while (!lcd_clicked());
  5422. st_synchronize();
  5423. target[E_AXIS] += bowden_length[snmm_extruder];
  5424. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 3000, active_extruder);
  5425. target[E_AXIS] += FIL_LOAD_LENGTH - 60;
  5426. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 1400, active_extruder);
  5427. target[E_AXIS] += 40;
  5428. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 400, active_extruder);
  5429. target[E_AXIS] += 10;
  5430. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 50, active_extruder);
  5431. #else
  5432. target[E_AXIS]+= FILAMENTCHANGE_FIRSTFEED ;
  5433. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EFEED, active_extruder);
  5434. #endif
  5435. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  5436. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EXFEED, active_extruder);
  5437. lcd_loading_filament();
  5438. break;
  5439. // Filament loaded properly but color is not clear
  5440. case 3:
  5441. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  5442. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  5443. lcd_loading_color();
  5444. break;
  5445. // Everything good
  5446. default:
  5447. lcd_change_success();
  5448. lcd_update_enable(true);
  5449. break;
  5450. }
  5451. }
  5452. //Not let's go back to print
  5453. fanSpeed = fanSpeedBckp;
  5454. //Feed a little of filament to stabilize pressure
  5455. target[E_AXIS]+= FILAMENTCHANGE_RECFEED;
  5456. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EXFEED, active_extruder);
  5457. //Retract
  5458. target[E_AXIS]+= FILAMENTCHANGE_FIRSTRETRACT;
  5459. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder);
  5460. //plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 70, active_extruder); //should do nothing
  5461. //Move XY back
  5462. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_XYFEED, active_extruder);
  5463. //Move Z back
  5464. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_ZFEED, active_extruder);
  5465. target[E_AXIS]= target[E_AXIS] - FILAMENTCHANGE_FIRSTRETRACT;
  5466. //Unretract
  5467. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder);
  5468. //Set E position to original
  5469. plan_set_e_position(lastpos[E_AXIS]);
  5470. //Recover feed rate
  5471. feedmultiply=feedmultiplyBckp;
  5472. char cmd[9];
  5473. sprintf_P(cmd, PSTR("M220 S%i"), feedmultiplyBckp);
  5474. enquecommand(cmd);
  5475. lcd_setstatuspgm(_T(WELCOME_MSG));
  5476. custom_message = false;
  5477. custom_message_type = 0;
  5478. #ifdef PAT9125
  5479. fsensor_enabled = old_fsensor_enabled; //temporary solution for unexpected restarting
  5480. if (fsensor_M600)
  5481. {
  5482. cmdqueue_pop_front(); //hack because M600 repeated 2x when enqueued to front
  5483. st_synchronize();
  5484. while (!is_buffer_empty())
  5485. {
  5486. process_commands();
  5487. cmdqueue_pop_front();
  5488. }
  5489. fsensor_enable();
  5490. fsensor_restore_print_and_continue();
  5491. }
  5492. #endif //PAT9125
  5493. }
  5494. break;
  5495. #endif //FILAMENTCHANGEENABLE
  5496. case 601: {
  5497. if(lcd_commands_type == 0) lcd_commands_type = LCD_COMMAND_LONG_PAUSE;
  5498. }
  5499. break;
  5500. case 602: {
  5501. if(lcd_commands_type == 0) lcd_commands_type = LCD_COMMAND_LONG_PAUSE_RESUME;
  5502. }
  5503. break;
  5504. #ifdef PINDA_THERMISTOR
  5505. case 860: // M860 - Wait for PINDA thermistor to reach target temperature.
  5506. {
  5507. int setTargetPinda = 0;
  5508. if (code_seen('S')) {
  5509. setTargetPinda = code_value();
  5510. }
  5511. else {
  5512. break;
  5513. }
  5514. LCD_MESSAGERPGM(_T(MSG_PLEASE_WAIT));
  5515. SERIAL_PROTOCOLPGM("Wait for PINDA target temperature:");
  5516. SERIAL_PROTOCOL(setTargetPinda);
  5517. SERIAL_PROTOCOLLN("");
  5518. codenum = millis();
  5519. cancel_heatup = false;
  5520. KEEPALIVE_STATE(NOT_BUSY);
  5521. while ((!cancel_heatup) && current_temperature_pinda < setTargetPinda) {
  5522. if ((millis() - codenum) > 1000) //Print Temp Reading every 1 second while waiting.
  5523. {
  5524. SERIAL_PROTOCOLPGM("P:");
  5525. SERIAL_PROTOCOL_F(current_temperature_pinda, 1);
  5526. SERIAL_PROTOCOLPGM("/");
  5527. SERIAL_PROTOCOL(setTargetPinda);
  5528. SERIAL_PROTOCOLLN("");
  5529. codenum = millis();
  5530. }
  5531. manage_heater();
  5532. manage_inactivity();
  5533. lcd_update();
  5534. }
  5535. LCD_MESSAGERPGM(_T(MSG_OK));
  5536. break;
  5537. }
  5538. case 861: // M861 - Set/Read PINDA temperature compensation offsets
  5539. if (code_seen('?')) { // ? - Print out current EEPROM offset values
  5540. uint8_t cal_status = calibration_status_pinda();
  5541. int16_t usteps = 0;
  5542. cal_status ? SERIAL_PROTOCOLLN("PINDA cal status: 1") : SERIAL_PROTOCOLLN("PINDA cal status: 0");
  5543. SERIAL_PROTOCOLLN("index, temp, ustep, um");
  5544. for (uint8_t i = 0; i < 6; i++)
  5545. {
  5546. if(i>0) EEPROM_read_B(EEPROM_PROBE_TEMP_SHIFT + (i-1) * 2, &usteps);
  5547. float mm = ((float)usteps) / axis_steps_per_unit[Z_AXIS];
  5548. i == 0 ? SERIAL_PROTOCOLPGM("n/a") : SERIAL_PROTOCOL(i - 1);
  5549. SERIAL_PROTOCOLPGM(", ");
  5550. SERIAL_PROTOCOL(35 + (i * 5));
  5551. SERIAL_PROTOCOLPGM(", ");
  5552. SERIAL_PROTOCOL(usteps);
  5553. SERIAL_PROTOCOLPGM(", ");
  5554. SERIAL_PROTOCOL(mm * 1000);
  5555. SERIAL_PROTOCOLLN("");
  5556. }
  5557. }
  5558. else if (code_seen('!')) { // ! - Set factory default values
  5559. eeprom_write_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 1);
  5560. int16_t z_shift = 8; //40C - 20um - 8usteps
  5561. EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT, &z_shift);
  5562. z_shift = 24; //45C - 60um - 24usteps
  5563. EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + 2, &z_shift);
  5564. z_shift = 48; //50C - 120um - 48usteps
  5565. EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + 4, &z_shift);
  5566. z_shift = 80; //55C - 200um - 80usteps
  5567. EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + 6, &z_shift);
  5568. z_shift = 120; //60C - 300um - 120usteps
  5569. EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + 8, &z_shift);
  5570. SERIAL_PROTOCOLLN("factory restored");
  5571. }
  5572. else if (code_seen('Z')) { // Z - Set all values to 0 (effectively disabling PINDA temperature compensation)
  5573. eeprom_write_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 1);
  5574. int16_t z_shift = 0;
  5575. for (uint8_t i = 0; i < 5; i++) EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + i * 2, &z_shift);
  5576. SERIAL_PROTOCOLLN("zerorized");
  5577. }
  5578. else if (code_seen('S')) { // Sxxx Iyyy - Set compensation ustep value S for compensation table index I
  5579. int16_t usteps = code_value();
  5580. if (code_seen('I')) {
  5581. byte index = code_value();
  5582. if ((index >= 0) && (index < 5)) {
  5583. EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + index * 2, &usteps);
  5584. SERIAL_PROTOCOLLN("OK");
  5585. SERIAL_PROTOCOLLN("index, temp, ustep, um");
  5586. for (uint8_t i = 0; i < 6; i++)
  5587. {
  5588. usteps = 0;
  5589. if (i>0) EEPROM_read_B(EEPROM_PROBE_TEMP_SHIFT + (i - 1) * 2, &usteps);
  5590. float mm = ((float)usteps) / axis_steps_per_unit[Z_AXIS];
  5591. i == 0 ? SERIAL_PROTOCOLPGM("n/a") : SERIAL_PROTOCOL(i - 1);
  5592. SERIAL_PROTOCOLPGM(", ");
  5593. SERIAL_PROTOCOL(35 + (i * 5));
  5594. SERIAL_PROTOCOLPGM(", ");
  5595. SERIAL_PROTOCOL(usteps);
  5596. SERIAL_PROTOCOLPGM(", ");
  5597. SERIAL_PROTOCOL(mm * 1000);
  5598. SERIAL_PROTOCOLLN("");
  5599. }
  5600. }
  5601. }
  5602. }
  5603. else {
  5604. SERIAL_PROTOCOLPGM("no valid command");
  5605. }
  5606. break;
  5607. #endif //PINDA_THERMISTOR
  5608. #ifdef LIN_ADVANCE
  5609. case 900: // M900: Set LIN_ADVANCE options.
  5610. gcode_M900();
  5611. break;
  5612. #endif
  5613. case 907: // M907 Set digital trimpot motor current using axis codes.
  5614. {
  5615. #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
  5616. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) st_current_set(i,code_value());
  5617. if(code_seen('B')) st_current_set(4,code_value());
  5618. if(code_seen('S')) for(int i=0;i<=4;i++) st_current_set(i,code_value());
  5619. #endif
  5620. #ifdef MOTOR_CURRENT_PWM_XY_PIN
  5621. if(code_seen('X')) st_current_set(0, code_value());
  5622. #endif
  5623. #ifdef MOTOR_CURRENT_PWM_Z_PIN
  5624. if(code_seen('Z')) st_current_set(1, code_value());
  5625. #endif
  5626. #ifdef MOTOR_CURRENT_PWM_E_PIN
  5627. if(code_seen('E')) st_current_set(2, code_value());
  5628. #endif
  5629. }
  5630. break;
  5631. case 908: // M908 Control digital trimpot directly.
  5632. {
  5633. #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
  5634. uint8_t channel,current;
  5635. if(code_seen('P')) channel=code_value();
  5636. if(code_seen('S')) current=code_value();
  5637. digitalPotWrite(channel, current);
  5638. #endif
  5639. }
  5640. break;
  5641. #ifdef TMC2130
  5642. case 910: // M910 TMC2130 init
  5643. {
  5644. tmc2130_init();
  5645. }
  5646. break;
  5647. case 911: // M911 Set TMC2130 holding currents
  5648. {
  5649. if (code_seen('X')) tmc2130_set_current_h(0, code_value());
  5650. if (code_seen('Y')) tmc2130_set_current_h(1, code_value());
  5651. if (code_seen('Z')) tmc2130_set_current_h(2, code_value());
  5652. if (code_seen('E')) tmc2130_set_current_h(3, code_value());
  5653. }
  5654. break;
  5655. case 912: // M912 Set TMC2130 running currents
  5656. {
  5657. if (code_seen('X')) tmc2130_set_current_r(0, code_value());
  5658. if (code_seen('Y')) tmc2130_set_current_r(1, code_value());
  5659. if (code_seen('Z')) tmc2130_set_current_r(2, code_value());
  5660. if (code_seen('E')) tmc2130_set_current_r(3, code_value());
  5661. }
  5662. break;
  5663. case 913: // M913 Print TMC2130 currents
  5664. {
  5665. tmc2130_print_currents();
  5666. }
  5667. break;
  5668. case 914: // M914 Set normal mode
  5669. {
  5670. tmc2130_mode = TMC2130_MODE_NORMAL;
  5671. tmc2130_init();
  5672. }
  5673. break;
  5674. case 915: // M915 Set silent mode
  5675. {
  5676. tmc2130_mode = TMC2130_MODE_SILENT;
  5677. tmc2130_init();
  5678. }
  5679. break;
  5680. case 916: // M916 Set sg_thrs
  5681. {
  5682. if (code_seen('X')) tmc2130_sg_thr[X_AXIS] = code_value();
  5683. if (code_seen('Y')) tmc2130_sg_thr[Y_AXIS] = code_value();
  5684. if (code_seen('Z')) tmc2130_sg_thr[Z_AXIS] = code_value();
  5685. if (code_seen('E')) tmc2130_sg_thr[E_AXIS] = code_value();
  5686. MYSERIAL.print("tmc2130_sg_thr[X]=");
  5687. MYSERIAL.println(tmc2130_sg_thr[X_AXIS], DEC);
  5688. MYSERIAL.print("tmc2130_sg_thr[Y]=");
  5689. MYSERIAL.println(tmc2130_sg_thr[Y_AXIS], DEC);
  5690. MYSERIAL.print("tmc2130_sg_thr[Z]=");
  5691. MYSERIAL.println(tmc2130_sg_thr[Z_AXIS], DEC);
  5692. MYSERIAL.print("tmc2130_sg_thr[E]=");
  5693. MYSERIAL.println(tmc2130_sg_thr[E_AXIS], DEC);
  5694. }
  5695. break;
  5696. case 917: // M917 Set TMC2130 pwm_ampl
  5697. {
  5698. if (code_seen('X')) tmc2130_set_pwm_ampl(0, code_value());
  5699. if (code_seen('Y')) tmc2130_set_pwm_ampl(1, code_value());
  5700. if (code_seen('Z')) tmc2130_set_pwm_ampl(2, code_value());
  5701. if (code_seen('E')) tmc2130_set_pwm_ampl(3, code_value());
  5702. }
  5703. break;
  5704. case 918: // M918 Set TMC2130 pwm_grad
  5705. {
  5706. if (code_seen('X')) tmc2130_set_pwm_grad(0, code_value());
  5707. if (code_seen('Y')) tmc2130_set_pwm_grad(1, code_value());
  5708. if (code_seen('Z')) tmc2130_set_pwm_grad(2, code_value());
  5709. if (code_seen('E')) tmc2130_set_pwm_grad(3, code_value());
  5710. }
  5711. break;
  5712. #endif //TMC2130
  5713. case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
  5714. {
  5715. #ifdef TMC2130
  5716. if(code_seen('E'))
  5717. {
  5718. uint16_t res_new = code_value();
  5719. if ((res_new == 8) || (res_new == 16) || (res_new == 32) || (res_new == 64) || (res_new == 128))
  5720. {
  5721. st_synchronize();
  5722. uint8_t axis = E_AXIS;
  5723. uint16_t res = tmc2130_get_res(axis);
  5724. tmc2130_set_res(axis, res_new);
  5725. if (res_new > res)
  5726. {
  5727. uint16_t fac = (res_new / res);
  5728. axis_steps_per_unit[axis] *= fac;
  5729. position[E_AXIS] *= fac;
  5730. }
  5731. else
  5732. {
  5733. uint16_t fac = (res / res_new);
  5734. axis_steps_per_unit[axis] /= fac;
  5735. position[E_AXIS] /= fac;
  5736. }
  5737. }
  5738. }
  5739. #else //TMC2130
  5740. #if defined(X_MS1_PIN) && X_MS1_PIN > -1
  5741. if(code_seen('S')) for(int i=0;i<=4;i++) microstep_mode(i,code_value());
  5742. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_mode(i,(uint8_t)code_value());
  5743. if(code_seen('B')) microstep_mode(4,code_value());
  5744. microstep_readings();
  5745. #endif
  5746. #endif //TMC2130
  5747. }
  5748. break;
  5749. case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low.
  5750. {
  5751. #if defined(X_MS1_PIN) && X_MS1_PIN > -1
  5752. if(code_seen('S')) switch((int)code_value())
  5753. {
  5754. case 1:
  5755. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_ms(i,code_value(),-1);
  5756. if(code_seen('B')) microstep_ms(4,code_value(),-1);
  5757. break;
  5758. case 2:
  5759. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_ms(i,-1,code_value());
  5760. if(code_seen('B')) microstep_ms(4,-1,code_value());
  5761. break;
  5762. }
  5763. microstep_readings();
  5764. #endif
  5765. }
  5766. break;
  5767. case 701: //M701: load filament
  5768. {
  5769. gcode_M701();
  5770. }
  5771. break;
  5772. case 702:
  5773. {
  5774. #ifdef SNMM
  5775. if (code_seen('U')) {
  5776. extr_unload_used(); //unload all filaments which were used in current print
  5777. }
  5778. else if (code_seen('C')) {
  5779. extr_unload(); //unload just current filament
  5780. }
  5781. else {
  5782. extr_unload_all(); //unload all filaments
  5783. }
  5784. #else
  5785. #ifdef PAT9125
  5786. bool old_fsensor_enabled = fsensor_enabled;
  5787. fsensor_enabled = false;
  5788. #endif //PAT9125
  5789. custom_message = true;
  5790. custom_message_type = 2;
  5791. lcd_setstatuspgm(_T(MSG_UNLOADING_FILAMENT));
  5792. // extr_unload2();
  5793. current_position[E_AXIS] -= 45;
  5794. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 5200 / 60, active_extruder);
  5795. st_synchronize();
  5796. current_position[E_AXIS] -= 15;
  5797. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 1000 / 60, active_extruder);
  5798. st_synchronize();
  5799. current_position[E_AXIS] -= 20;
  5800. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 1000 / 60, active_extruder);
  5801. st_synchronize();
  5802. lcd_display_message_fullscreen_P(_T(MSG_PULL_OUT_FILAMENT));
  5803. //disable extruder steppers so filament can be removed
  5804. disable_e0();
  5805. disable_e1();
  5806. disable_e2();
  5807. delay(100);
  5808. WRITE(BEEPER, HIGH);
  5809. uint8_t counterBeep = 0;
  5810. while (!lcd_clicked() && (counterBeep < 50)) {
  5811. if (counterBeep > 5) WRITE(BEEPER, LOW);
  5812. delay_keep_alive(100);
  5813. counterBeep++;
  5814. }
  5815. WRITE(BEEPER, LOW);
  5816. st_synchronize();
  5817. while (lcd_clicked()) delay_keep_alive(100);
  5818. lcd_update_enable(true);
  5819. lcd_setstatuspgm(_T(WELCOME_MSG));
  5820. custom_message = false;
  5821. custom_message_type = 0;
  5822. #ifdef PAT9125
  5823. fsensor_enabled = old_fsensor_enabled;
  5824. #endif //PAT9125
  5825. #endif
  5826. }
  5827. break;
  5828. case 999: // M999: Restart after being stopped
  5829. Stopped = false;
  5830. lcd_reset_alert_level();
  5831. gcode_LastN = Stopped_gcode_LastN;
  5832. FlushSerialRequestResend();
  5833. break;
  5834. default:
  5835. printf_P(PSTR("Unknown M code: %s \n"), cmdbuffer + bufindr + CMDHDRSIZE);
  5836. }
  5837. } // end if(code_seen('M')) (end of M codes)
  5838. else if(code_seen('T'))
  5839. {
  5840. int index;
  5841. st_synchronize();
  5842. for (index = 1; *(strchr_pointer + index) == ' ' || *(strchr_pointer + index) == '\t'; index++);
  5843. if ((*(strchr_pointer + index) < '0' || *(strchr_pointer + index) > '9') && *(strchr_pointer + index) != '?') {
  5844. SERIAL_ECHOLNPGM("Invalid T code.");
  5845. }
  5846. else {
  5847. if (*(strchr_pointer + index) == '?') {
  5848. tmp_extruder = choose_extruder_menu();
  5849. }
  5850. else {
  5851. tmp_extruder = code_value();
  5852. }
  5853. snmm_filaments_used |= (1 << tmp_extruder); //for stop print
  5854. #ifdef SNMM
  5855. #ifdef LIN_ADVANCE
  5856. if (snmm_extruder != tmp_extruder)
  5857. clear_current_adv_vars(); //Check if the selected extruder is not the active one and reset LIN_ADVANCE variables if so.
  5858. #endif
  5859. snmm_extruder = tmp_extruder;
  5860. delay(100);
  5861. disable_e0();
  5862. disable_e1();
  5863. disable_e2();
  5864. pinMode(E_MUX0_PIN, OUTPUT);
  5865. pinMode(E_MUX1_PIN, OUTPUT);
  5866. delay(100);
  5867. SERIAL_ECHO_START;
  5868. SERIAL_ECHO("T:");
  5869. SERIAL_ECHOLN((int)tmp_extruder);
  5870. switch (tmp_extruder) {
  5871. case 1:
  5872. WRITE(E_MUX0_PIN, HIGH);
  5873. WRITE(E_MUX1_PIN, LOW);
  5874. break;
  5875. case 2:
  5876. WRITE(E_MUX0_PIN, LOW);
  5877. WRITE(E_MUX1_PIN, HIGH);
  5878. break;
  5879. case 3:
  5880. WRITE(E_MUX0_PIN, HIGH);
  5881. WRITE(E_MUX1_PIN, HIGH);
  5882. break;
  5883. default:
  5884. WRITE(E_MUX0_PIN, LOW);
  5885. WRITE(E_MUX1_PIN, LOW);
  5886. break;
  5887. }
  5888. delay(100);
  5889. #else
  5890. if (tmp_extruder >= EXTRUDERS) {
  5891. SERIAL_ECHO_START;
  5892. SERIAL_ECHOPGM("T");
  5893. SERIAL_PROTOCOLLN((int)tmp_extruder);
  5894. SERIAL_ECHOLNRPGM(_n("Invalid extruder"));////MSG_INVALID_EXTRUDER c=0 r=0
  5895. }
  5896. else {
  5897. boolean make_move = false;
  5898. if (code_seen('F')) {
  5899. make_move = true;
  5900. next_feedrate = code_value();
  5901. if (next_feedrate > 0.0) {
  5902. feedrate = next_feedrate;
  5903. }
  5904. }
  5905. #if EXTRUDERS > 1
  5906. if (tmp_extruder != active_extruder) {
  5907. // Save current position to return to after applying extruder offset
  5908. memcpy(destination, current_position, sizeof(destination));
  5909. // Offset extruder (only by XY)
  5910. int i;
  5911. for (i = 0; i < 2; i++) {
  5912. current_position[i] = current_position[i] -
  5913. extruder_offset[i][active_extruder] +
  5914. extruder_offset[i][tmp_extruder];
  5915. }
  5916. // Set the new active extruder and position
  5917. active_extruder = tmp_extruder;
  5918. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  5919. // Move to the old position if 'F' was in the parameters
  5920. if (make_move && Stopped == false) {
  5921. prepare_move();
  5922. }
  5923. }
  5924. #endif
  5925. SERIAL_ECHO_START;
  5926. SERIAL_ECHORPGM(_n("Active Extruder: "));////MSG_ACTIVE_EXTRUDER c=0 r=0
  5927. SERIAL_PROTOCOLLN((int)active_extruder);
  5928. }
  5929. #endif
  5930. }
  5931. } // end if(code_seen('T')) (end of T codes)
  5932. #ifdef DEBUG_DCODES
  5933. else if (code_seen('D')) // D codes (debug)
  5934. {
  5935. switch((int)code_value())
  5936. {
  5937. case -1: // D-1 - Endless loop
  5938. dcode__1(); break;
  5939. case 0: // D0 - Reset
  5940. dcode_0(); break;
  5941. case 1: // D1 - Clear EEPROM
  5942. dcode_1(); break;
  5943. case 2: // D2 - Read/Write RAM
  5944. dcode_2(); break;
  5945. case 3: // D3 - Read/Write EEPROM
  5946. dcode_3(); break;
  5947. case 4: // D4 - Read/Write PIN
  5948. dcode_4(); break;
  5949. case 5: // D5 - Read/Write FLASH
  5950. // dcode_5(); break;
  5951. break;
  5952. case 6: // D6 - Read/Write external FLASH
  5953. dcode_6(); break;
  5954. case 7: // D7 - Read/Write Bootloader
  5955. dcode_7(); break;
  5956. case 8: // D8 - Read/Write PINDA
  5957. dcode_8(); break;
  5958. case 9: // D9 - Read/Write ADC
  5959. dcode_9(); break;
  5960. case 10: // D10 - XYZ calibration = OK
  5961. dcode_10(); break;
  5962. #ifdef TMC2130
  5963. case 2130: // D9125 - TMC2130
  5964. dcode_2130(); break;
  5965. #endif //TMC2130
  5966. #ifdef PAT9125
  5967. case 9125: // D9125 - PAT9125
  5968. dcode_9125(); break;
  5969. #endif //PAT9125
  5970. }
  5971. }
  5972. #endif //DEBUG_DCODES
  5973. else
  5974. {
  5975. SERIAL_ECHO_START;
  5976. SERIAL_ECHORPGM(MSG_UNKNOWN_COMMAND);
  5977. SERIAL_ECHO(CMDBUFFER_CURRENT_STRING);
  5978. SERIAL_ECHOLNPGM("\"(2)");
  5979. }
  5980. KEEPALIVE_STATE(NOT_BUSY);
  5981. ClearToSend();
  5982. }
  5983. void FlushSerialRequestResend()
  5984. {
  5985. //char cmdbuffer[bufindr][100]="Resend:";
  5986. MYSERIAL.flush();
  5987. SERIAL_PROTOCOLRPGM(_i("Resend: "));////MSG_RESEND c=0 r=0
  5988. SERIAL_PROTOCOLLN(gcode_LastN + 1);
  5989. previous_millis_cmd = millis();
  5990. SERIAL_PROTOCOLLNRPGM(_T(MSG_OK));
  5991. }
  5992. // Confirm the execution of a command, if sent from a serial line.
  5993. // Execution of a command from a SD card will not be confirmed.
  5994. void ClearToSend()
  5995. {
  5996. previous_millis_cmd = millis();
  5997. if (CMDBUFFER_CURRENT_TYPE == CMDBUFFER_CURRENT_TYPE_USB)
  5998. SERIAL_PROTOCOLLNRPGM(_T(MSG_OK));
  5999. }
  6000. #if MOTHERBOARD == BOARD_RAMBO_MINI_1_0 || MOTHERBOARD == BOARD_RAMBO_MINI_1_3
  6001. void update_currents() {
  6002. float current_high[3] = DEFAULT_PWM_MOTOR_CURRENT_LOUD;
  6003. float current_low[3] = DEFAULT_PWM_MOTOR_CURRENT;
  6004. float tmp_motor[3];
  6005. //SERIAL_ECHOLNPGM("Currents updated: ");
  6006. if (destination[Z_AXIS] < Z_SILENT) {
  6007. //SERIAL_ECHOLNPGM("LOW");
  6008. for (uint8_t i = 0; i < 3; i++) {
  6009. st_current_set(i, current_low[i]);
  6010. /*MYSERIAL.print(int(i));
  6011. SERIAL_ECHOPGM(": ");
  6012. MYSERIAL.println(current_low[i]);*/
  6013. }
  6014. }
  6015. else if (destination[Z_AXIS] > Z_HIGH_POWER) {
  6016. //SERIAL_ECHOLNPGM("HIGH");
  6017. for (uint8_t i = 0; i < 3; i++) {
  6018. st_current_set(i, current_high[i]);
  6019. /*MYSERIAL.print(int(i));
  6020. SERIAL_ECHOPGM(": ");
  6021. MYSERIAL.println(current_high[i]);*/
  6022. }
  6023. }
  6024. else {
  6025. for (uint8_t i = 0; i < 3; i++) {
  6026. float q = current_low[i] - Z_SILENT*((current_high[i] - current_low[i]) / (Z_HIGH_POWER - Z_SILENT));
  6027. tmp_motor[i] = ((current_high[i] - current_low[i]) / (Z_HIGH_POWER - Z_SILENT))*destination[Z_AXIS] + q;
  6028. st_current_set(i, tmp_motor[i]);
  6029. /*MYSERIAL.print(int(i));
  6030. SERIAL_ECHOPGM(": ");
  6031. MYSERIAL.println(tmp_motor[i]);*/
  6032. }
  6033. }
  6034. }
  6035. #endif //MOTHERBOARD == BOARD_RAMBO_MINI_1_0 || MOTHERBOARD == BOARD_RAMBO_MINI_1_3
  6036. void get_coordinates()
  6037. {
  6038. bool seen[4]={false,false,false,false};
  6039. for(int8_t i=0; i < NUM_AXIS; i++) {
  6040. if(code_seen(axis_codes[i]))
  6041. {
  6042. bool relative = axis_relative_modes[i] || relative_mode;
  6043. destination[i] = (float)code_value();
  6044. if (i == E_AXIS) {
  6045. float emult = extruder_multiplier[active_extruder];
  6046. if (emult != 1.) {
  6047. if (! relative) {
  6048. destination[i] -= current_position[i];
  6049. relative = true;
  6050. }
  6051. destination[i] *= emult;
  6052. }
  6053. }
  6054. if (relative)
  6055. destination[i] += current_position[i];
  6056. seen[i]=true;
  6057. #if MOTHERBOARD == BOARD_RAMBO_MINI_1_0 || MOTHERBOARD == BOARD_RAMBO_MINI_1_3
  6058. if (i == Z_AXIS && SilentModeMenu == SILENT_MODE_AUTO) update_currents();
  6059. #endif //MOTHERBOARD == BOARD_RAMBO_MINI_1_0 || MOTHERBOARD == BOARD_RAMBO_MINI_1_3
  6060. }
  6061. else destination[i] = current_position[i]; //Are these else lines really needed?
  6062. }
  6063. if(code_seen('F')) {
  6064. next_feedrate = code_value();
  6065. #ifdef MAX_SILENT_FEEDRATE
  6066. if (tmc2130_mode == TMC2130_MODE_SILENT)
  6067. if (next_feedrate > MAX_SILENT_FEEDRATE) next_feedrate = MAX_SILENT_FEEDRATE;
  6068. #endif //MAX_SILENT_FEEDRATE
  6069. if(next_feedrate > 0.0) feedrate = next_feedrate;
  6070. if (!seen[0] && !seen[1] && !seen[2] && seen[3])
  6071. {
  6072. // float e_max_speed =
  6073. // printf_P(PSTR("E MOVE speed %7.3f\n"), feedrate / 60)
  6074. }
  6075. }
  6076. }
  6077. void get_arc_coordinates()
  6078. {
  6079. #ifdef SF_ARC_FIX
  6080. bool relative_mode_backup = relative_mode;
  6081. relative_mode = true;
  6082. #endif
  6083. get_coordinates();
  6084. #ifdef SF_ARC_FIX
  6085. relative_mode=relative_mode_backup;
  6086. #endif
  6087. if(code_seen('I')) {
  6088. offset[0] = code_value();
  6089. }
  6090. else {
  6091. offset[0] = 0.0;
  6092. }
  6093. if(code_seen('J')) {
  6094. offset[1] = code_value();
  6095. }
  6096. else {
  6097. offset[1] = 0.0;
  6098. }
  6099. }
  6100. void clamp_to_software_endstops(float target[3])
  6101. {
  6102. #ifdef DEBUG_DISABLE_SWLIMITS
  6103. return;
  6104. #endif //DEBUG_DISABLE_SWLIMITS
  6105. world2machine_clamp(target[0], target[1]);
  6106. // Clamp the Z coordinate.
  6107. if (min_software_endstops) {
  6108. float negative_z_offset = 0;
  6109. #ifdef ENABLE_AUTO_BED_LEVELING
  6110. if (Z_PROBE_OFFSET_FROM_EXTRUDER < 0) negative_z_offset = negative_z_offset + Z_PROBE_OFFSET_FROM_EXTRUDER;
  6111. if (add_homing[Z_AXIS] < 0) negative_z_offset = negative_z_offset + add_homing[Z_AXIS];
  6112. #endif
  6113. if (target[Z_AXIS] < min_pos[Z_AXIS]+negative_z_offset) target[Z_AXIS] = min_pos[Z_AXIS]+negative_z_offset;
  6114. }
  6115. if (max_software_endstops) {
  6116. if (target[Z_AXIS] > max_pos[Z_AXIS]) target[Z_AXIS] = max_pos[Z_AXIS];
  6117. }
  6118. }
  6119. #ifdef MESH_BED_LEVELING
  6120. void mesh_plan_buffer_line(const float &x, const float &y, const float &z, const float &e, const float &feed_rate, const uint8_t extruder) {
  6121. float dx = x - current_position[X_AXIS];
  6122. float dy = y - current_position[Y_AXIS];
  6123. float dz = z - current_position[Z_AXIS];
  6124. int n_segments = 0;
  6125. if (mbl.active) {
  6126. float len = abs(dx) + abs(dy);
  6127. if (len > 0)
  6128. // Split to 3cm segments or shorter.
  6129. n_segments = int(ceil(len / 30.f));
  6130. }
  6131. if (n_segments > 1) {
  6132. float de = e - current_position[E_AXIS];
  6133. for (int i = 1; i < n_segments; ++ i) {
  6134. float t = float(i) / float(n_segments);
  6135. plan_buffer_line(
  6136. current_position[X_AXIS] + t * dx,
  6137. current_position[Y_AXIS] + t * dy,
  6138. current_position[Z_AXIS] + t * dz,
  6139. current_position[E_AXIS] + t * de,
  6140. feed_rate, extruder);
  6141. }
  6142. }
  6143. // The rest of the path.
  6144. plan_buffer_line(x, y, z, e, feed_rate, extruder);
  6145. current_position[X_AXIS] = x;
  6146. current_position[Y_AXIS] = y;
  6147. current_position[Z_AXIS] = z;
  6148. current_position[E_AXIS] = e;
  6149. }
  6150. #endif // MESH_BED_LEVELING
  6151. void prepare_move()
  6152. {
  6153. clamp_to_software_endstops(destination);
  6154. previous_millis_cmd = millis();
  6155. // Do not use feedmultiply for E or Z only moves
  6156. if( (current_position[X_AXIS] == destination [X_AXIS]) && (current_position[Y_AXIS] == destination [Y_AXIS])) {
  6157. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  6158. }
  6159. else {
  6160. #ifdef MESH_BED_LEVELING
  6161. mesh_plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply*(1./(60.f*100.f)), active_extruder);
  6162. #else
  6163. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply*(1./(60.f*100.f)), active_extruder);
  6164. #endif
  6165. }
  6166. for(int8_t i=0; i < NUM_AXIS; i++) {
  6167. current_position[i] = destination[i];
  6168. }
  6169. }
  6170. void prepare_arc_move(char isclockwise) {
  6171. float r = hypot(offset[X_AXIS], offset[Y_AXIS]); // Compute arc radius for mc_arc
  6172. // Trace the arc
  6173. mc_arc(current_position, destination, offset, X_AXIS, Y_AXIS, Z_AXIS, feedrate*feedmultiply/60/100.0, r, isclockwise, active_extruder);
  6174. // As far as the parser is concerned, the position is now == target. In reality the
  6175. // motion control system might still be processing the action and the real tool position
  6176. // in any intermediate location.
  6177. for(int8_t i=0; i < NUM_AXIS; i++) {
  6178. current_position[i] = destination[i];
  6179. }
  6180. previous_millis_cmd = millis();
  6181. }
  6182. #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
  6183. #if defined(FAN_PIN)
  6184. #if CONTROLLERFAN_PIN == FAN_PIN
  6185. #error "You cannot set CONTROLLERFAN_PIN equal to FAN_PIN"
  6186. #endif
  6187. #endif
  6188. unsigned long lastMotor = 0; //Save the time for when a motor was turned on last
  6189. unsigned long lastMotorCheck = 0;
  6190. void controllerFan()
  6191. {
  6192. if ((millis() - lastMotorCheck) >= 2500) //Not a time critical function, so we only check every 2500ms
  6193. {
  6194. lastMotorCheck = millis();
  6195. if(!READ(X_ENABLE_PIN) || !READ(Y_ENABLE_PIN) || !READ(Z_ENABLE_PIN) || (soft_pwm_bed > 0)
  6196. #if EXTRUDERS > 2
  6197. || !READ(E2_ENABLE_PIN)
  6198. #endif
  6199. #if EXTRUDER > 1
  6200. #if defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1
  6201. || !READ(X2_ENABLE_PIN)
  6202. #endif
  6203. || !READ(E1_ENABLE_PIN)
  6204. #endif
  6205. || !READ(E0_ENABLE_PIN)) //If any of the drivers are enabled...
  6206. {
  6207. lastMotor = millis(); //... set time to NOW so the fan will turn on
  6208. }
  6209. if ((millis() - lastMotor) >= (CONTROLLERFAN_SECS*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC...
  6210. {
  6211. digitalWrite(CONTROLLERFAN_PIN, 0);
  6212. analogWrite(CONTROLLERFAN_PIN, 0);
  6213. }
  6214. else
  6215. {
  6216. // allows digital or PWM fan output to be used (see M42 handling)
  6217. digitalWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
  6218. analogWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
  6219. }
  6220. }
  6221. }
  6222. #endif
  6223. #ifdef TEMP_STAT_LEDS
  6224. static bool blue_led = false;
  6225. static bool red_led = false;
  6226. static uint32_t stat_update = 0;
  6227. void handle_status_leds(void) {
  6228. float max_temp = 0.0;
  6229. if(millis() > stat_update) {
  6230. stat_update += 500; // Update every 0.5s
  6231. for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
  6232. max_temp = max(max_temp, degHotend(cur_extruder));
  6233. max_temp = max(max_temp, degTargetHotend(cur_extruder));
  6234. }
  6235. #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
  6236. max_temp = max(max_temp, degTargetBed());
  6237. max_temp = max(max_temp, degBed());
  6238. #endif
  6239. if((max_temp > 55.0) && (red_led == false)) {
  6240. digitalWrite(STAT_LED_RED, 1);
  6241. digitalWrite(STAT_LED_BLUE, 0);
  6242. red_led = true;
  6243. blue_led = false;
  6244. }
  6245. if((max_temp < 54.0) && (blue_led == false)) {
  6246. digitalWrite(STAT_LED_RED, 0);
  6247. digitalWrite(STAT_LED_BLUE, 1);
  6248. red_led = false;
  6249. blue_led = true;
  6250. }
  6251. }
  6252. }
  6253. #endif
  6254. #ifdef SAFETYTIMER
  6255. /**
  6256. * @brief Turn off heating after 30 minutes of inactivity
  6257. *
  6258. * Full screen blocking notification message is shown after heater turning off.
  6259. * Paused print is not considered inactivity, as nozzle is cooled anyway and bed cooling would
  6260. * damage print.
  6261. */
  6262. static void handleSafetyTimer()
  6263. {
  6264. #if (EXTRUDERS > 1)
  6265. #error Implemented only for one extruder.
  6266. #endif //(EXTRUDERS > 1)
  6267. static Timer safetyTimer;
  6268. if (IS_SD_PRINTING || is_usb_printing || isPrintPaused || (custom_message_type == 4)
  6269. || (lcd_commands_type == LCD_COMMAND_V2_CAL) || (!degTargetBed() && !degTargetHotend(0)))
  6270. {
  6271. safetyTimer.stop();
  6272. }
  6273. else if ((degTargetBed() || degTargetHotend(0)) && (!safetyTimer.running()))
  6274. {
  6275. safetyTimer.start();
  6276. }
  6277. else if (safetyTimer.expired(1800000ul))
  6278. {
  6279. setTargetBed(0);
  6280. setTargetHotend(0, 0);
  6281. lcd_show_fullscreen_message_and_wait_P(_i("Heating disabled by safety timer."));////MSG_BED_HEATING_SAFETY_DISABLED c=0 r=0
  6282. }
  6283. }
  6284. #endif //SAFETYTIMER
  6285. void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument set in Marlin.h
  6286. {
  6287. #ifdef PAT9125
  6288. if (fsensor_enabled && filament_autoload_enabled && !fsensor_M600 && !moves_planned() && !IS_SD_PRINTING && !is_usb_printing && (lcd_commands_type != LCD_COMMAND_V2_CAL))
  6289. {
  6290. if (fsensor_autoload_enabled)
  6291. {
  6292. if (fsensor_check_autoload())
  6293. {
  6294. if (degHotend0() > EXTRUDE_MINTEMP)
  6295. {
  6296. fsensor_autoload_check_stop();
  6297. tone(BEEPER, 1000);
  6298. delay_keep_alive(50);
  6299. noTone(BEEPER);
  6300. loading_flag = true;
  6301. enquecommand_front_P((PSTR("M701")));
  6302. }
  6303. else
  6304. {
  6305. lcd_update_enable(false);
  6306. lcd_implementation_clear();
  6307. lcd.setCursor(0, 0);
  6308. lcd_printPGM(_T(MSG_ERROR));
  6309. lcd.setCursor(0, 2);
  6310. lcd_printPGM(_T(MSG_PREHEAT_NOZZLE));
  6311. delay(2000);
  6312. lcd_implementation_clear();
  6313. lcd_update_enable(true);
  6314. }
  6315. }
  6316. }
  6317. else
  6318. fsensor_autoload_check_start();
  6319. }
  6320. else
  6321. if (fsensor_autoload_enabled)
  6322. fsensor_autoload_check_stop();
  6323. #endif //PAT9125
  6324. #ifdef SAFETYTIMER
  6325. handleSafetyTimer();
  6326. #endif //SAFETYTIMER
  6327. #if defined(KILL_PIN) && KILL_PIN > -1
  6328. static int killCount = 0; // make the inactivity button a bit less responsive
  6329. const int KILL_DELAY = 10000;
  6330. #endif
  6331. if(buflen < (BUFSIZE-1)){
  6332. get_command();
  6333. }
  6334. if( (millis() - previous_millis_cmd) > max_inactive_time )
  6335. if(max_inactive_time)
  6336. kill("", 4);
  6337. if(stepper_inactive_time) {
  6338. if( (millis() - previous_millis_cmd) > stepper_inactive_time )
  6339. {
  6340. if(blocks_queued() == false && ignore_stepper_queue == false) {
  6341. disable_x();
  6342. // SERIAL_ECHOLNPGM("manage_inactivity - disable Y");
  6343. disable_y();
  6344. disable_z();
  6345. disable_e0();
  6346. disable_e1();
  6347. disable_e2();
  6348. }
  6349. }
  6350. }
  6351. #ifdef CHDK //Check if pin should be set to LOW after M240 set it to HIGH
  6352. if (chdkActive && (millis() - chdkHigh > CHDK_DELAY))
  6353. {
  6354. chdkActive = false;
  6355. WRITE(CHDK, LOW);
  6356. }
  6357. #endif
  6358. #if defined(KILL_PIN) && KILL_PIN > -1
  6359. // Check if the kill button was pressed and wait just in case it was an accidental
  6360. // key kill key press
  6361. // -------------------------------------------------------------------------------
  6362. if( 0 == READ(KILL_PIN) )
  6363. {
  6364. killCount++;
  6365. }
  6366. else if (killCount > 0)
  6367. {
  6368. killCount--;
  6369. }
  6370. // Exceeded threshold and we can confirm that it was not accidental
  6371. // KILL the machine
  6372. // ----------------------------------------------------------------
  6373. if ( killCount >= KILL_DELAY)
  6374. {
  6375. kill("", 5);
  6376. }
  6377. #endif
  6378. #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
  6379. controllerFan(); //Check if fan should be turned on to cool stepper drivers down
  6380. #endif
  6381. #ifdef EXTRUDER_RUNOUT_PREVENT
  6382. if( (millis() - previous_millis_cmd) > EXTRUDER_RUNOUT_SECONDS*1000 )
  6383. if(degHotend(active_extruder)>EXTRUDER_RUNOUT_MINTEMP)
  6384. {
  6385. bool oldstatus=READ(E0_ENABLE_PIN);
  6386. enable_e0();
  6387. float oldepos=current_position[E_AXIS];
  6388. float oldedes=destination[E_AXIS];
  6389. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS],
  6390. destination[E_AXIS]+EXTRUDER_RUNOUT_EXTRUDE*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS],
  6391. EXTRUDER_RUNOUT_SPEED/60.*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS], active_extruder);
  6392. current_position[E_AXIS]=oldepos;
  6393. destination[E_AXIS]=oldedes;
  6394. plan_set_e_position(oldepos);
  6395. previous_millis_cmd=millis();
  6396. st_synchronize();
  6397. WRITE(E0_ENABLE_PIN,oldstatus);
  6398. }
  6399. #endif
  6400. #ifdef TEMP_STAT_LEDS
  6401. handle_status_leds();
  6402. #endif
  6403. check_axes_activity();
  6404. }
  6405. void kill(const char *full_screen_message, unsigned char id)
  6406. {
  6407. SERIAL_ECHOPGM("KILL: ");
  6408. MYSERIAL.println(int(id));
  6409. //return;
  6410. cli(); // Stop interrupts
  6411. disable_heater();
  6412. disable_x();
  6413. // SERIAL_ECHOLNPGM("kill - disable Y");
  6414. disable_y();
  6415. disable_z();
  6416. disable_e0();
  6417. disable_e1();
  6418. disable_e2();
  6419. #if defined(PS_ON_PIN) && PS_ON_PIN > -1
  6420. pinMode(PS_ON_PIN,INPUT);
  6421. #endif
  6422. SERIAL_ERROR_START;
  6423. SERIAL_ERRORLNRPGM(_i("Printer halted. kill() called!"));////MSG_ERR_KILLED c=0 r=0
  6424. if (full_screen_message != NULL) {
  6425. SERIAL_ERRORLNRPGM(full_screen_message);
  6426. lcd_display_message_fullscreen_P(full_screen_message);
  6427. } else {
  6428. LCD_ALERTMESSAGERPGM(_i("KILLED. "));////MSG_KILLED c=0 r=0
  6429. }
  6430. // FMC small patch to update the LCD before ending
  6431. sei(); // enable interrupts
  6432. for ( int i=5; i--; lcd_update())
  6433. {
  6434. delay(200);
  6435. }
  6436. cli(); // disable interrupts
  6437. suicide();
  6438. while(1)
  6439. {
  6440. #ifdef WATCHDOG
  6441. wdt_reset();
  6442. #endif //WATCHDOG
  6443. /* Intentionally left empty */
  6444. } // Wait for reset
  6445. }
  6446. void Stop()
  6447. {
  6448. disable_heater();
  6449. if(Stopped == false) {
  6450. Stopped = true;
  6451. Stopped_gcode_LastN = gcode_LastN; // Save last g_code for restart
  6452. SERIAL_ERROR_START;
  6453. SERIAL_ERRORLNRPGM(_T(MSG_ERR_STOPPED));
  6454. LCD_MESSAGERPGM(_T(MSG_STOPPED));
  6455. }
  6456. }
  6457. bool IsStopped() { return Stopped; };
  6458. #ifdef FAST_PWM_FAN
  6459. void setPwmFrequency(uint8_t pin, int val)
  6460. {
  6461. val &= 0x07;
  6462. switch(digitalPinToTimer(pin))
  6463. {
  6464. #if defined(TCCR0A)
  6465. case TIMER0A:
  6466. case TIMER0B:
  6467. // TCCR0B &= ~(_BV(CS00) | _BV(CS01) | _BV(CS02));
  6468. // TCCR0B |= val;
  6469. break;
  6470. #endif
  6471. #if defined(TCCR1A)
  6472. case TIMER1A:
  6473. case TIMER1B:
  6474. // TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
  6475. // TCCR1B |= val;
  6476. break;
  6477. #endif
  6478. #if defined(TCCR2)
  6479. case TIMER2:
  6480. case TIMER2:
  6481. TCCR2 &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
  6482. TCCR2 |= val;
  6483. break;
  6484. #endif
  6485. #if defined(TCCR2A)
  6486. case TIMER2A:
  6487. case TIMER2B:
  6488. TCCR2B &= ~(_BV(CS20) | _BV(CS21) | _BV(CS22));
  6489. TCCR2B |= val;
  6490. break;
  6491. #endif
  6492. #if defined(TCCR3A)
  6493. case TIMER3A:
  6494. case TIMER3B:
  6495. case TIMER3C:
  6496. TCCR3B &= ~(_BV(CS30) | _BV(CS31) | _BV(CS32));
  6497. TCCR3B |= val;
  6498. break;
  6499. #endif
  6500. #if defined(TCCR4A)
  6501. case TIMER4A:
  6502. case TIMER4B:
  6503. case TIMER4C:
  6504. TCCR4B &= ~(_BV(CS40) | _BV(CS41) | _BV(CS42));
  6505. TCCR4B |= val;
  6506. break;
  6507. #endif
  6508. #if defined(TCCR5A)
  6509. case TIMER5A:
  6510. case TIMER5B:
  6511. case TIMER5C:
  6512. TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52));
  6513. TCCR5B |= val;
  6514. break;
  6515. #endif
  6516. }
  6517. }
  6518. #endif //FAST_PWM_FAN
  6519. bool setTargetedHotend(int code){
  6520. tmp_extruder = active_extruder;
  6521. if(code_seen('T')) {
  6522. tmp_extruder = code_value();
  6523. if(tmp_extruder >= EXTRUDERS) {
  6524. SERIAL_ECHO_START;
  6525. switch(code){
  6526. case 104:
  6527. SERIAL_ECHORPGM(_i("M104 Invalid extruder "));////MSG_M104_INVALID_EXTRUDER c=0 r=0
  6528. break;
  6529. case 105:
  6530. SERIAL_ECHO(_i("M105 Invalid extruder "));////MSG_M105_INVALID_EXTRUDER c=0 r=0
  6531. break;
  6532. case 109:
  6533. SERIAL_ECHO(_i("M109 Invalid extruder "));////MSG_M109_INVALID_EXTRUDER c=0 r=0
  6534. break;
  6535. case 218:
  6536. SERIAL_ECHO(_i("M218 Invalid extruder "));////MSG_M218_INVALID_EXTRUDER c=0 r=0
  6537. break;
  6538. case 221:
  6539. SERIAL_ECHO(_i("M221 Invalid extruder "));////MSG_M221_INVALID_EXTRUDER c=0 r=0
  6540. break;
  6541. }
  6542. SERIAL_PROTOCOLLN((int)tmp_extruder);
  6543. return true;
  6544. }
  6545. }
  6546. return false;
  6547. }
  6548. void save_statistics(unsigned long _total_filament_used, unsigned long _total_print_time) //_total_filament_used unit: mm/100; print time in s
  6549. {
  6550. if (eeprom_read_byte((uint8_t *)EEPROM_TOTALTIME) == 255 && eeprom_read_byte((uint8_t *)EEPROM_TOTALTIME + 1) == 255 && eeprom_read_byte((uint8_t *)EEPROM_TOTALTIME + 2) == 255 && eeprom_read_byte((uint8_t *)EEPROM_TOTALTIME + 3) == 255)
  6551. {
  6552. eeprom_update_dword((uint32_t *)EEPROM_TOTALTIME, 0);
  6553. eeprom_update_dword((uint32_t *)EEPROM_FILAMENTUSED, 0);
  6554. }
  6555. unsigned long _previous_filament = eeprom_read_dword((uint32_t *)EEPROM_FILAMENTUSED); //_previous_filament unit: cm
  6556. unsigned long _previous_time = eeprom_read_dword((uint32_t *)EEPROM_TOTALTIME); //_previous_time unit: min
  6557. eeprom_update_dword((uint32_t *)EEPROM_TOTALTIME, _previous_time + (_total_print_time/60)); //EEPROM_TOTALTIME unit: min
  6558. eeprom_update_dword((uint32_t *)EEPROM_FILAMENTUSED, _previous_filament + (_total_filament_used / 1000));
  6559. total_filament_used = 0;
  6560. }
  6561. float calculate_extruder_multiplier(float diameter) {
  6562. float out = 1.f;
  6563. if (volumetric_enabled && diameter > 0.f) {
  6564. float area = M_PI * diameter * diameter * 0.25;
  6565. out = 1.f / area;
  6566. }
  6567. if (extrudemultiply != 100)
  6568. out *= float(extrudemultiply) * 0.01f;
  6569. return out;
  6570. }
  6571. void calculate_extruder_multipliers() {
  6572. extruder_multiplier[0] = calculate_extruder_multiplier(filament_size[0]);
  6573. #if EXTRUDERS > 1
  6574. extruder_multiplier[1] = calculate_extruder_multiplier(filament_size[1]);
  6575. #if EXTRUDERS > 2
  6576. extruder_multiplier[2] = calculate_extruder_multiplier(filament_size[2]);
  6577. #endif
  6578. #endif
  6579. }
  6580. void delay_keep_alive(unsigned int ms)
  6581. {
  6582. for (;;) {
  6583. manage_heater();
  6584. // Manage inactivity, but don't disable steppers on timeout.
  6585. manage_inactivity(true);
  6586. lcd_update();
  6587. if (ms == 0)
  6588. break;
  6589. else if (ms >= 50) {
  6590. delay(50);
  6591. ms -= 50;
  6592. } else {
  6593. delay(ms);
  6594. ms = 0;
  6595. }
  6596. }
  6597. }
  6598. void wait_for_heater(long codenum) {
  6599. #ifdef TEMP_RESIDENCY_TIME
  6600. long residencyStart;
  6601. residencyStart = -1;
  6602. /* continue to loop until we have reached the target temp
  6603. _and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */
  6604. while ((!cancel_heatup) && ((residencyStart == -1) ||
  6605. (residencyStart >= 0 && (((unsigned int)(millis() - residencyStart)) < (TEMP_RESIDENCY_TIME * 1000UL))))) {
  6606. #else
  6607. while (target_direction ? (isHeatingHotend(tmp_extruder)) : (isCoolingHotend(tmp_extruder) && (CooldownNoWait == false))) {
  6608. #endif //TEMP_RESIDENCY_TIME
  6609. if ((millis() - codenum) > 1000UL)
  6610. { //Print Temp Reading and remaining time every 1 second while heating up/cooling down
  6611. if (!farm_mode) {
  6612. SERIAL_PROTOCOLPGM("T:");
  6613. SERIAL_PROTOCOL_F(degHotend(tmp_extruder), 1);
  6614. SERIAL_PROTOCOLPGM(" E:");
  6615. SERIAL_PROTOCOL((int)tmp_extruder);
  6616. #ifdef TEMP_RESIDENCY_TIME
  6617. SERIAL_PROTOCOLPGM(" W:");
  6618. if (residencyStart > -1)
  6619. {
  6620. codenum = ((TEMP_RESIDENCY_TIME * 1000UL) - (millis() - residencyStart)) / 1000UL;
  6621. SERIAL_PROTOCOLLN(codenum);
  6622. }
  6623. else
  6624. {
  6625. SERIAL_PROTOCOLLN("?");
  6626. }
  6627. }
  6628. #else
  6629. SERIAL_PROTOCOLLN("");
  6630. #endif
  6631. codenum = millis();
  6632. }
  6633. manage_heater();
  6634. manage_inactivity();
  6635. lcd_update();
  6636. #ifdef TEMP_RESIDENCY_TIME
  6637. /* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
  6638. or when current temp falls outside the hysteresis after target temp was reached */
  6639. if ((residencyStart == -1 && target_direction && (degHotend(tmp_extruder) >= (degTargetHotend(tmp_extruder) - TEMP_WINDOW))) ||
  6640. (residencyStart == -1 && !target_direction && (degHotend(tmp_extruder) <= (degTargetHotend(tmp_extruder) + TEMP_WINDOW))) ||
  6641. (residencyStart > -1 && labs(degHotend(tmp_extruder) - degTargetHotend(tmp_extruder)) > TEMP_HYSTERESIS))
  6642. {
  6643. residencyStart = millis();
  6644. }
  6645. #endif //TEMP_RESIDENCY_TIME
  6646. }
  6647. }
  6648. void check_babystep() {
  6649. int babystep_z;
  6650. EEPROM_read_B(EEPROM_BABYSTEP_Z, &babystep_z);
  6651. if ((babystep_z < Z_BABYSTEP_MIN) || (babystep_z > Z_BABYSTEP_MAX)) {
  6652. babystep_z = 0; //if babystep value is out of min max range, set it to 0
  6653. SERIAL_ECHOLNPGM("Z live adjust out of range. Setting to 0");
  6654. EEPROM_save_B(EEPROM_BABYSTEP_Z, &babystep_z);
  6655. lcd_show_fullscreen_message_and_wait_P(PSTR("Z live adjust out of range. Setting to 0. Click to continue."));
  6656. lcd_update_enable(true);
  6657. }
  6658. }
  6659. #ifdef DIS
  6660. void d_setup()
  6661. {
  6662. pinMode(D_DATACLOCK, INPUT_PULLUP);
  6663. pinMode(D_DATA, INPUT_PULLUP);
  6664. pinMode(D_REQUIRE, OUTPUT);
  6665. digitalWrite(D_REQUIRE, HIGH);
  6666. }
  6667. float d_ReadData()
  6668. {
  6669. int digit[13];
  6670. String mergeOutput;
  6671. float output;
  6672. digitalWrite(D_REQUIRE, HIGH);
  6673. for (int i = 0; i<13; i++)
  6674. {
  6675. for (int j = 0; j < 4; j++)
  6676. {
  6677. while (digitalRead(D_DATACLOCK) == LOW) {}
  6678. while (digitalRead(D_DATACLOCK) == HIGH) {}
  6679. bitWrite(digit[i], j, digitalRead(D_DATA));
  6680. }
  6681. }
  6682. digitalWrite(D_REQUIRE, LOW);
  6683. mergeOutput = "";
  6684. output = 0;
  6685. for (int r = 5; r <= 10; r++) //Merge digits
  6686. {
  6687. mergeOutput += digit[r];
  6688. }
  6689. output = mergeOutput.toFloat();
  6690. if (digit[4] == 8) //Handle sign
  6691. {
  6692. output *= -1;
  6693. }
  6694. for (int i = digit[11]; i > 0; i--) //Handle floating point
  6695. {
  6696. output /= 10;
  6697. }
  6698. return output;
  6699. }
  6700. void bed_analysis(float x_dimension, float y_dimension, int x_points_num, int y_points_num, float shift_x, float shift_y) {
  6701. int t1 = 0;
  6702. int t_delay = 0;
  6703. int digit[13];
  6704. int m;
  6705. char str[3];
  6706. //String mergeOutput;
  6707. char mergeOutput[15];
  6708. float output;
  6709. int mesh_point = 0; //index number of calibration point
  6710. float bed_zero_ref_x = (-22.f + X_PROBE_OFFSET_FROM_EXTRUDER); //shift between zero point on bed and target and between probe and nozzle
  6711. float bed_zero_ref_y = (-0.6f + Y_PROBE_OFFSET_FROM_EXTRUDER);
  6712. float mesh_home_z_search = 4;
  6713. float row[x_points_num];
  6714. int ix = 0;
  6715. int iy = 0;
  6716. char* filename_wldsd = "wldsd.txt";
  6717. char data_wldsd[70];
  6718. char numb_wldsd[10];
  6719. d_setup();
  6720. if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS])) {
  6721. // We don't know where we are! HOME!
  6722. // Push the commands to the front of the message queue in the reverse order!
  6723. // There shall be always enough space reserved for these commands.
  6724. repeatcommand_front(); // repeat G80 with all its parameters
  6725. enquecommand_front_P((PSTR("G28 W0")));
  6726. enquecommand_front_P((PSTR("G1 Z5")));
  6727. return;
  6728. }
  6729. bool custom_message_old = custom_message;
  6730. unsigned int custom_message_type_old = custom_message_type;
  6731. unsigned int custom_message_state_old = custom_message_state;
  6732. custom_message = true;
  6733. custom_message_type = 1;
  6734. custom_message_state = (x_points_num * y_points_num) + 10;
  6735. lcd_update(1);
  6736. mbl.reset();
  6737. babystep_undo();
  6738. card.openFile(filename_wldsd, false);
  6739. current_position[Z_AXIS] = mesh_home_z_search;
  6740. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 60, active_extruder);
  6741. int XY_AXIS_FEEDRATE = homing_feedrate[X_AXIS] / 20;
  6742. int Z_PROBE_FEEDRATE = homing_feedrate[Z_AXIS] / 60;
  6743. int Z_LIFT_FEEDRATE = homing_feedrate[Z_AXIS] / 40;
  6744. setup_for_endstop_move(false);
  6745. SERIAL_PROTOCOLPGM("Num X,Y: ");
  6746. SERIAL_PROTOCOL(x_points_num);
  6747. SERIAL_PROTOCOLPGM(",");
  6748. SERIAL_PROTOCOL(y_points_num);
  6749. SERIAL_PROTOCOLPGM("\nZ search height: ");
  6750. SERIAL_PROTOCOL(mesh_home_z_search);
  6751. SERIAL_PROTOCOLPGM("\nDimension X,Y: ");
  6752. SERIAL_PROTOCOL(x_dimension);
  6753. SERIAL_PROTOCOLPGM(",");
  6754. SERIAL_PROTOCOL(y_dimension);
  6755. SERIAL_PROTOCOLLNPGM("\nMeasured points:");
  6756. while (mesh_point != x_points_num * y_points_num) {
  6757. ix = mesh_point % x_points_num; // from 0 to MESH_NUM_X_POINTS - 1
  6758. iy = mesh_point / x_points_num;
  6759. if (iy & 1) ix = (x_points_num - 1) - ix; // Zig zag
  6760. float z0 = 0.f;
  6761. current_position[Z_AXIS] = mesh_home_z_search;
  6762. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], Z_LIFT_FEEDRATE, active_extruder);
  6763. st_synchronize();
  6764. current_position[X_AXIS] = 13.f + ix * (x_dimension / (x_points_num - 1)) - bed_zero_ref_x + shift_x;
  6765. current_position[Y_AXIS] = 6.4f + iy * (y_dimension / (y_points_num - 1)) - bed_zero_ref_y + shift_y;
  6766. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], XY_AXIS_FEEDRATE, active_extruder);
  6767. st_synchronize();
  6768. if (!find_bed_induction_sensor_point_z(-10.f)) { //if we have data from z calibration max allowed difference is 1mm for each point, if we dont have data max difference is 10mm from initial point
  6769. break;
  6770. card.closefile();
  6771. }
  6772. //memset(numb_wldsd, 0, sizeof(numb_wldsd));
  6773. //dtostrf(d_ReadData(), 8, 5, numb_wldsd);
  6774. //strcat(data_wldsd, numb_wldsd);
  6775. //MYSERIAL.println(data_wldsd);
  6776. //delay(1000);
  6777. //delay(3000);
  6778. //t1 = millis();
  6779. //while (digitalRead(D_DATACLOCK) == LOW) {}
  6780. //while (digitalRead(D_DATACLOCK) == HIGH) {}
  6781. memset(digit, 0, sizeof(digit));
  6782. //cli();
  6783. digitalWrite(D_REQUIRE, LOW);
  6784. for (int i = 0; i<13; i++)
  6785. {
  6786. //t1 = millis();
  6787. for (int j = 0; j < 4; j++)
  6788. {
  6789. while (digitalRead(D_DATACLOCK) == LOW) {}
  6790. while (digitalRead(D_DATACLOCK) == HIGH) {}
  6791. bitWrite(digit[i], j, digitalRead(D_DATA));
  6792. }
  6793. //t_delay = (millis() - t1);
  6794. //SERIAL_PROTOCOLPGM(" ");
  6795. //SERIAL_PROTOCOL_F(t_delay, 5);
  6796. //SERIAL_PROTOCOLPGM(" ");
  6797. }
  6798. //sei();
  6799. digitalWrite(D_REQUIRE, HIGH);
  6800. mergeOutput[0] = '\0';
  6801. output = 0;
  6802. for (int r = 5; r <= 10; r++) //Merge digits
  6803. {
  6804. sprintf(str, "%d", digit[r]);
  6805. strcat(mergeOutput, str);
  6806. }
  6807. output = atof(mergeOutput);
  6808. if (digit[4] == 8) //Handle sign
  6809. {
  6810. output *= -1;
  6811. }
  6812. for (int i = digit[11]; i > 0; i--) //Handle floating point
  6813. {
  6814. output *= 0.1;
  6815. }
  6816. //output = d_ReadData();
  6817. //row[ix] = current_position[Z_AXIS];
  6818. memset(data_wldsd, 0, sizeof(data_wldsd));
  6819. for (int i = 0; i <3; i++) {
  6820. memset(numb_wldsd, 0, sizeof(numb_wldsd));
  6821. dtostrf(current_position[i], 8, 5, numb_wldsd);
  6822. strcat(data_wldsd, numb_wldsd);
  6823. strcat(data_wldsd, ";");
  6824. }
  6825. memset(numb_wldsd, 0, sizeof(numb_wldsd));
  6826. dtostrf(output, 8, 5, numb_wldsd);
  6827. strcat(data_wldsd, numb_wldsd);
  6828. //strcat(data_wldsd, ";");
  6829. card.write_command(data_wldsd);
  6830. //row[ix] = d_ReadData();
  6831. row[ix] = output; // current_position[Z_AXIS];
  6832. if (iy % 2 == 1 ? ix == 0 : ix == x_points_num - 1) {
  6833. for (int i = 0; i < x_points_num; i++) {
  6834. SERIAL_PROTOCOLPGM(" ");
  6835. SERIAL_PROTOCOL_F(row[i], 5);
  6836. }
  6837. SERIAL_PROTOCOLPGM("\n");
  6838. }
  6839. custom_message_state--;
  6840. mesh_point++;
  6841. lcd_update(1);
  6842. }
  6843. card.closefile();
  6844. }
  6845. #endif
  6846. void temp_compensation_start() {
  6847. custom_message = true;
  6848. custom_message_type = 5;
  6849. custom_message_state = PINDA_HEAT_T + 1;
  6850. lcd_update(2);
  6851. if (degHotend(active_extruder) > EXTRUDE_MINTEMP) {
  6852. current_position[E_AXIS] -= DEFAULT_RETRACTION;
  6853. }
  6854. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 400, active_extruder);
  6855. current_position[X_AXIS] = PINDA_PREHEAT_X;
  6856. current_position[Y_AXIS] = PINDA_PREHEAT_Y;
  6857. current_position[Z_AXIS] = PINDA_PREHEAT_Z;
  6858. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
  6859. st_synchronize();
  6860. while (fabs(degBed() - target_temperature_bed) > 1) delay_keep_alive(1000);
  6861. for (int i = 0; i < PINDA_HEAT_T; i++) {
  6862. delay_keep_alive(1000);
  6863. custom_message_state = PINDA_HEAT_T - i;
  6864. if (custom_message_state == 99 || custom_message_state == 9) lcd_update(2); //force whole display redraw if number of digits changed
  6865. else lcd_update(1);
  6866. }
  6867. custom_message_type = 0;
  6868. custom_message_state = 0;
  6869. custom_message = false;
  6870. }
  6871. void temp_compensation_apply() {
  6872. int i_add;
  6873. int compensation_value;
  6874. int z_shift = 0;
  6875. float z_shift_mm;
  6876. if (calibration_status() == CALIBRATION_STATUS_CALIBRATED) {
  6877. if (target_temperature_bed % 10 == 0 && target_temperature_bed >= 60 && target_temperature_bed <= 100) {
  6878. i_add = (target_temperature_bed - 60) / 10;
  6879. EEPROM_read_B(EEPROM_PROBE_TEMP_SHIFT + i_add * 2, &z_shift);
  6880. z_shift_mm = z_shift / axis_steps_per_unit[Z_AXIS];
  6881. }else {
  6882. //interpolation
  6883. z_shift_mm = temp_comp_interpolation(target_temperature_bed) / axis_steps_per_unit[Z_AXIS];
  6884. }
  6885. SERIAL_PROTOCOLPGM("\n");
  6886. SERIAL_PROTOCOLPGM("Z shift applied:");
  6887. MYSERIAL.print(z_shift_mm);
  6888. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] - z_shift_mm, current_position[E_AXIS], homing_feedrate[Z_AXIS] / 40, active_extruder);
  6889. st_synchronize();
  6890. plan_set_z_position(current_position[Z_AXIS]);
  6891. }
  6892. else {
  6893. //we have no temp compensation data
  6894. }
  6895. }
  6896. float temp_comp_interpolation(float inp_temperature) {
  6897. //cubic spline interpolation
  6898. int n, i, j, k;
  6899. float h[10], a, b, c, d, sum, s[10] = { 0 }, x[10], F[10], f[10], m[10][10] = { 0 }, temp;
  6900. int shift[10];
  6901. int temp_C[10];
  6902. n = 6; //number of measured points
  6903. shift[0] = 0;
  6904. for (i = 0; i < n; i++) {
  6905. if (i>0) EEPROM_read_B(EEPROM_PROBE_TEMP_SHIFT + (i-1) * 2, &shift[i]); //read shift in steps from EEPROM
  6906. temp_C[i] = 50 + i * 10; //temperature in C
  6907. #ifdef PINDA_THERMISTOR
  6908. temp_C[i] = 35 + i * 5; //temperature in C
  6909. #else
  6910. temp_C[i] = 50 + i * 10; //temperature in C
  6911. #endif
  6912. x[i] = (float)temp_C[i];
  6913. f[i] = (float)shift[i];
  6914. }
  6915. if (inp_temperature < x[0]) return 0;
  6916. for (i = n - 1; i>0; i--) {
  6917. F[i] = (f[i] - f[i - 1]) / (x[i] - x[i - 1]);
  6918. h[i - 1] = x[i] - x[i - 1];
  6919. }
  6920. //*********** formation of h, s , f matrix **************
  6921. for (i = 1; i<n - 1; i++) {
  6922. m[i][i] = 2 * (h[i - 1] + h[i]);
  6923. if (i != 1) {
  6924. m[i][i - 1] = h[i - 1];
  6925. m[i - 1][i] = h[i - 1];
  6926. }
  6927. m[i][n - 1] = 6 * (F[i + 1] - F[i]);
  6928. }
  6929. //*********** forward elimination **************
  6930. for (i = 1; i<n - 2; i++) {
  6931. temp = (m[i + 1][i] / m[i][i]);
  6932. for (j = 1; j <= n - 1; j++)
  6933. m[i + 1][j] -= temp*m[i][j];
  6934. }
  6935. //*********** backward substitution *********
  6936. for (i = n - 2; i>0; i--) {
  6937. sum = 0;
  6938. for (j = i; j <= n - 2; j++)
  6939. sum += m[i][j] * s[j];
  6940. s[i] = (m[i][n - 1] - sum) / m[i][i];
  6941. }
  6942. for (i = 0; i<n - 1; i++)
  6943. if ((x[i] <= inp_temperature && inp_temperature <= x[i + 1]) || (i == n-2 && inp_temperature > x[i + 1])) {
  6944. a = (s[i + 1] - s[i]) / (6 * h[i]);
  6945. b = s[i] / 2;
  6946. c = (f[i + 1] - f[i]) / h[i] - (2 * h[i] * s[i] + s[i + 1] * h[i]) / 6;
  6947. d = f[i];
  6948. sum = a*pow((inp_temperature - x[i]), 3) + b*pow((inp_temperature - x[i]), 2) + c*(inp_temperature - x[i]) + d;
  6949. }
  6950. return sum;
  6951. }
  6952. #ifdef PINDA_THERMISTOR
  6953. float temp_compensation_pinda_thermistor_offset(float temperature_pinda)
  6954. {
  6955. if (!temp_cal_active) return 0;
  6956. if (!calibration_status_pinda()) return 0;
  6957. return temp_comp_interpolation(temperature_pinda) / axis_steps_per_unit[Z_AXIS];
  6958. }
  6959. #endif //PINDA_THERMISTOR
  6960. void long_pause() //long pause print
  6961. {
  6962. st_synchronize();
  6963. //save currently set parameters to global variables
  6964. saved_feedmultiply = feedmultiply;
  6965. HotendTempBckp = degTargetHotend(active_extruder);
  6966. fanSpeedBckp = fanSpeed;
  6967. start_pause_print = millis();
  6968. //save position
  6969. pause_lastpos[X_AXIS] = current_position[X_AXIS];
  6970. pause_lastpos[Y_AXIS] = current_position[Y_AXIS];
  6971. pause_lastpos[Z_AXIS] = current_position[Z_AXIS];
  6972. pause_lastpos[E_AXIS] = current_position[E_AXIS];
  6973. //retract
  6974. current_position[E_AXIS] -= DEFAULT_RETRACTION;
  6975. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 400, active_extruder);
  6976. //lift z
  6977. current_position[Z_AXIS] += Z_PAUSE_LIFT;
  6978. if (current_position[Z_AXIS] > Z_MAX_POS) current_position[Z_AXIS] = Z_MAX_POS;
  6979. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 15, active_extruder);
  6980. //set nozzle target temperature to 0
  6981. setTargetHotend(0, 0);
  6982. setTargetHotend(0, 1);
  6983. setTargetHotend(0, 2);
  6984. //Move XY to side
  6985. current_position[X_AXIS] = X_PAUSE_POS;
  6986. current_position[Y_AXIS] = Y_PAUSE_POS;
  6987. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 50, active_extruder);
  6988. // Turn off the print fan
  6989. fanSpeed = 0;
  6990. st_synchronize();
  6991. }
  6992. void serialecho_temperatures() {
  6993. float tt = degHotend(active_extruder);
  6994. SERIAL_PROTOCOLPGM("T:");
  6995. SERIAL_PROTOCOL(tt);
  6996. SERIAL_PROTOCOLPGM(" E:");
  6997. SERIAL_PROTOCOL((int)active_extruder);
  6998. SERIAL_PROTOCOLPGM(" B:");
  6999. SERIAL_PROTOCOL_F(degBed(), 1);
  7000. SERIAL_PROTOCOLLN("");
  7001. }
  7002. extern uint32_t sdpos_atomic;
  7003. #ifdef UVLO_SUPPORT
  7004. void uvlo_()
  7005. {
  7006. unsigned long time_start = millis();
  7007. bool sd_print = card.sdprinting;
  7008. // Conserve power as soon as possible.
  7009. disable_x();
  7010. disable_y();
  7011. disable_e0();
  7012. #ifdef TMC2130
  7013. tmc2130_set_current_h(Z_AXIS, 20);
  7014. tmc2130_set_current_r(Z_AXIS, 20);
  7015. tmc2130_set_current_h(E_AXIS, 20);
  7016. tmc2130_set_current_r(E_AXIS, 20);
  7017. #endif //TMC2130
  7018. // Indicate that the interrupt has been triggered.
  7019. // SERIAL_ECHOLNPGM("UVLO");
  7020. // Read out the current Z motor microstep counter. This will be later used
  7021. // for reaching the zero full step before powering off.
  7022. uint16_t z_microsteps = 0;
  7023. #ifdef TMC2130
  7024. z_microsteps = tmc2130_rd_MSCNT(Z_TMC2130_CS);
  7025. #endif //TMC2130
  7026. // Calculate the file position, from which to resume this print.
  7027. long sd_position = sdpos_atomic; //atomic sd position of last command added in queue
  7028. {
  7029. uint16_t sdlen_planner = planner_calc_sd_length(); //length of sd commands in planner
  7030. sd_position -= sdlen_planner;
  7031. uint16_t sdlen_cmdqueue = cmdqueue_calc_sd_length(); //length of sd commands in cmdqueue
  7032. sd_position -= sdlen_cmdqueue;
  7033. if (sd_position < 0) sd_position = 0;
  7034. }
  7035. // Backup the feedrate in mm/min.
  7036. int feedrate_bckp = blocks_queued() ? (block_buffer[block_buffer_tail].nominal_speed * 60.f) : feedrate;
  7037. // After this call, the planner queue is emptied and the current_position is set to a current logical coordinate.
  7038. // The logical coordinate will likely differ from the machine coordinate if the skew calibration and mesh bed leveling
  7039. // are in action.
  7040. planner_abort_hard();
  7041. // Store the current extruder position.
  7042. eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION_E), st_get_position_mm(E_AXIS));
  7043. eeprom_update_byte((uint8_t*)EEPROM_UVLO_E_ABS, axis_relative_modes[3]?0:1);
  7044. // Clean the input command queue.
  7045. cmdqueue_reset();
  7046. card.sdprinting = false;
  7047. // card.closefile();
  7048. // Enable stepper driver interrupt to move Z axis.
  7049. // This should be fine as the planner and command queues are empty and the SD card printing is disabled.
  7050. //FIXME one may want to disable serial lines at this point of time to avoid interfering with the command queue,
  7051. // though it should not happen that the command queue is touched as the plan_buffer_line always succeed without blocking.
  7052. sei();
  7053. plan_buffer_line(
  7054. current_position[X_AXIS],
  7055. current_position[Y_AXIS],
  7056. current_position[Z_AXIS],
  7057. current_position[E_AXIS] - DEFAULT_RETRACTION,
  7058. 95, active_extruder);
  7059. st_synchronize();
  7060. disable_e0();
  7061. plan_buffer_line(
  7062. current_position[X_AXIS],
  7063. current_position[Y_AXIS],
  7064. current_position[Z_AXIS] + UVLO_Z_AXIS_SHIFT + float((1024 - z_microsteps + 7) >> 4) / axis_steps_per_unit[Z_AXIS],
  7065. current_position[E_AXIS] - DEFAULT_RETRACTION,
  7066. 40, active_extruder);
  7067. st_synchronize();
  7068. disable_e0();
  7069. plan_buffer_line(
  7070. current_position[X_AXIS],
  7071. current_position[Y_AXIS],
  7072. current_position[Z_AXIS] + UVLO_Z_AXIS_SHIFT + float((1024 - z_microsteps + 7) >> 4) / axis_steps_per_unit[Z_AXIS],
  7073. current_position[E_AXIS] - DEFAULT_RETRACTION,
  7074. 40, active_extruder);
  7075. st_synchronize();
  7076. disable_e0();
  7077. disable_z();
  7078. // Move Z up to the next 0th full step.
  7079. // Write the file position.
  7080. eeprom_update_dword((uint32_t*)(EEPROM_FILE_POSITION), sd_position);
  7081. // Store the mesh bed leveling offsets. This is 2*9=18 bytes, which takes 18*3.4us=52us in worst case.
  7082. for (int8_t mesh_point = 0; mesh_point < 9; ++ mesh_point) {
  7083. uint8_t ix = mesh_point % MESH_MEAS_NUM_X_POINTS; // from 0 to MESH_NUM_X_POINTS - 1
  7084. uint8_t iy = mesh_point / MESH_MEAS_NUM_X_POINTS;
  7085. // Scale the z value to 1u resolution.
  7086. int16_t v = mbl.active ? int16_t(floor(mbl.z_values[iy*3][ix*3] * 1000.f + 0.5f)) : 0;
  7087. eeprom_update_word((uint16_t*)(EEPROM_UVLO_MESH_BED_LEVELING+2*mesh_point), *reinterpret_cast<uint16_t*>(&v));
  7088. }
  7089. // Read out the current Z motor microstep counter. This will be later used
  7090. // for reaching the zero full step before powering off.
  7091. eeprom_update_word((uint16_t*)(EEPROM_UVLO_Z_MICROSTEPS), z_microsteps);
  7092. // Store the current position.
  7093. eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 0), current_position[X_AXIS]);
  7094. eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 4), current_position[Y_AXIS]);
  7095. eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION_Z), current_position[Z_AXIS]);
  7096. // Store the current feed rate, temperatures and fan speed.
  7097. EEPROM_save_B(EEPROM_UVLO_FEEDRATE, &feedrate_bckp);
  7098. eeprom_update_byte((uint8_t*)EEPROM_UVLO_TARGET_HOTEND, target_temperature[active_extruder]);
  7099. eeprom_update_byte((uint8_t*)EEPROM_UVLO_TARGET_BED, target_temperature_bed);
  7100. eeprom_update_byte((uint8_t*)EEPROM_UVLO_FAN_SPEED, fanSpeed);
  7101. // Finaly store the "power outage" flag.
  7102. if(sd_print) eeprom_update_byte((uint8_t*)EEPROM_UVLO, 1);
  7103. st_synchronize();
  7104. SERIAL_ECHOPGM("stps");
  7105. MYSERIAL.println(tmc2130_rd_MSCNT(Z_AXIS));
  7106. disable_z();
  7107. // Increment power failure counter
  7108. eeprom_update_byte((uint8_t*)EEPROM_POWER_COUNT, eeprom_read_byte((uint8_t*)EEPROM_POWER_COUNT) + 1);
  7109. eeprom_update_word((uint16_t*)EEPROM_POWER_COUNT_TOT, eeprom_read_word((uint16_t*)EEPROM_POWER_COUNT_TOT) + 1);
  7110. SERIAL_ECHOLNPGM("UVLO - end");
  7111. MYSERIAL.println(millis() - time_start);
  7112. #if 0
  7113. // Move the print head to the side of the print until all the power stored in the power supply capacitors is depleted.
  7114. current_position[X_AXIS] = (current_position[X_AXIS] < 0.5f * (X_MIN_POS + X_MAX_POS)) ? X_MIN_POS : X_MAX_POS;
  7115. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 500, active_extruder);
  7116. st_synchronize();
  7117. #endif
  7118. cli();
  7119. volatile unsigned int ppcount = 0;
  7120. SET_OUTPUT(BEEPER);
  7121. WRITE(BEEPER, HIGH);
  7122. for(ppcount = 0; ppcount < 2000; ppcount ++){
  7123. asm("nop");//50ns on 20Mhz, 62.5ns on 16Mhz
  7124. }
  7125. WRITE(BEEPER, LOW);
  7126. while(1){
  7127. #if 1
  7128. WRITE(BEEPER, LOW);
  7129. for(ppcount = 0; ppcount < 8000; ppcount ++){
  7130. asm("nop");//50ns on 20Mhz, 62.5ns on 16Mhz
  7131. }
  7132. #endif
  7133. };
  7134. }
  7135. #endif //UVLO_SUPPORT
  7136. #if (defined(FANCHECK) && defined(TACH_1) && (TACH_1 >-1))
  7137. void setup_fan_interrupt() {
  7138. //INT7
  7139. DDRE &= ~(1 << 7); //input pin
  7140. PORTE &= ~(1 << 7); //no internal pull-up
  7141. //start with sensing rising edge
  7142. EICRB &= ~(1 << 6);
  7143. EICRB |= (1 << 7);
  7144. //enable INT7 interrupt
  7145. EIMSK |= (1 << 7);
  7146. }
  7147. // The fan interrupt is triggered at maximum 325Hz (may be a bit more due to component tollerances),
  7148. // and it takes 4.24 us to process (the interrupt invocation overhead not taken into account).
  7149. ISR(INT7_vect) {
  7150. //measuring speed now works for fanSpeed > 18 (approximately), which is sufficient because MIN_PRINT_FAN_SPEED is higher
  7151. if (fanSpeed < MIN_PRINT_FAN_SPEED) return;
  7152. if ((1 << 6) & EICRB) { //interrupt was triggered by rising edge
  7153. t_fan_rising_edge = millis_nc();
  7154. }
  7155. else { //interrupt was triggered by falling edge
  7156. if ((millis_nc() - t_fan_rising_edge) >= FAN_PULSE_WIDTH_LIMIT) {//this pulse was from sensor and not from pwm
  7157. fan_edge_counter[1] += 2; //we are currently counting all edges so lets count two edges for one pulse
  7158. }
  7159. }
  7160. EICRB ^= (1 << 6); //change edge
  7161. }
  7162. #endif
  7163. #ifdef UVLO_SUPPORT
  7164. void setup_uvlo_interrupt() {
  7165. DDRE &= ~(1 << 4); //input pin
  7166. PORTE &= ~(1 << 4); //no internal pull-up
  7167. //sensing falling edge
  7168. EICRB |= (1 << 0);
  7169. EICRB &= ~(1 << 1);
  7170. //enable INT4 interrupt
  7171. EIMSK |= (1 << 4);
  7172. }
  7173. ISR(INT4_vect) {
  7174. EIMSK &= ~(1 << 4); //disable INT4 interrupt to make sure that this code will be executed just once
  7175. SERIAL_ECHOLNPGM("INT4");
  7176. if (IS_SD_PRINTING) uvlo_();
  7177. }
  7178. void recover_print(uint8_t automatic) {
  7179. char cmd[30];
  7180. lcd_update_enable(true);
  7181. lcd_update(2);
  7182. lcd_setstatuspgm(_i("Recovering print "));////MSG_RECOVERING_PRINT c=20 r=1
  7183. recover_machine_state_after_power_panic();
  7184. // Set the target bed and nozzle temperatures.
  7185. sprintf_P(cmd, PSTR("M104 S%d"), target_temperature[active_extruder]);
  7186. enquecommand(cmd);
  7187. sprintf_P(cmd, PSTR("M140 S%d"), target_temperature_bed);
  7188. enquecommand(cmd);
  7189. // Lift the print head, so one may remove the excess priming material.
  7190. if (current_position[Z_AXIS] < 25)
  7191. enquecommand_P(PSTR("G1 Z25 F800"));
  7192. // Home X and Y axes. Homing just X and Y shall not touch the babystep and the world2machine transformation status.
  7193. enquecommand_P(PSTR("G28 X Y"));
  7194. // Set the target bed and nozzle temperatures and wait.
  7195. sprintf_P(cmd, PSTR("M109 S%d"), target_temperature[active_extruder]);
  7196. enquecommand(cmd);
  7197. sprintf_P(cmd, PSTR("M190 S%d"), target_temperature_bed);
  7198. enquecommand(cmd);
  7199. enquecommand_P(PSTR("M83")); //E axis relative mode
  7200. //enquecommand_P(PSTR("G1 E5 F120")); //Extrude some filament to stabilize pessure
  7201. // If not automatically recoreverd (long power loss), extrude extra filament to stabilize
  7202. if(automatic == 0){
  7203. enquecommand_P(PSTR("G1 E5 F120")); //Extrude some filament to stabilize pessure
  7204. }
  7205. enquecommand_P(PSTR("G1 E" STRINGIFY(-DEFAULT_RETRACTION)" F480"));
  7206. // Mark the power panic status as inactive.
  7207. eeprom_update_byte((uint8_t*)EEPROM_UVLO, 0);
  7208. /*while ((abs(degHotend(0)- target_temperature[0])>5) || (abs(degBed() -target_temperature_bed)>3)) { //wait for heater and bed to reach target temp
  7209. delay_keep_alive(1000);
  7210. }*/
  7211. SERIAL_ECHOPGM("After waiting for temp:");
  7212. SERIAL_ECHOPGM("Current position X_AXIS:");
  7213. MYSERIAL.println(current_position[X_AXIS]);
  7214. SERIAL_ECHOPGM("Current position Y_AXIS:");
  7215. MYSERIAL.println(current_position[Y_AXIS]);
  7216. // Restart the print.
  7217. restore_print_from_eeprom();
  7218. SERIAL_ECHOPGM("current_position[Z_AXIS]:");
  7219. MYSERIAL.print(current_position[Z_AXIS]);
  7220. SERIAL_ECHOPGM("current_position[E_AXIS]:");
  7221. MYSERIAL.print(current_position[E_AXIS]);
  7222. }
  7223. void recover_machine_state_after_power_panic()
  7224. {
  7225. char cmd[30];
  7226. // 1) Recover the logical cordinates at the time of the power panic.
  7227. // The logical XY coordinates are needed to recover the machine Z coordinate corrected by the mesh bed leveling.
  7228. current_position[X_AXIS] = eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 0));
  7229. current_position[Y_AXIS] = eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 4));
  7230. // Recover the logical coordinate of the Z axis at the time of the power panic.
  7231. // The current position after power panic is moved to the next closest 0th full step.
  7232. current_position[Z_AXIS] = eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION_Z)) +
  7233. UVLO_Z_AXIS_SHIFT + float((1024 - eeprom_read_word((uint16_t*)(EEPROM_UVLO_Z_MICROSTEPS)) + 7) >> 4) / axis_steps_per_unit[Z_AXIS];
  7234. if (eeprom_read_byte((uint8_t*)EEPROM_UVLO_E_ABS)) {
  7235. current_position[E_AXIS] = eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION_E));
  7236. sprintf_P(cmd, PSTR("G92 E"));
  7237. dtostrf(current_position[E_AXIS], 6, 3, cmd + strlen(cmd));
  7238. enquecommand(cmd);
  7239. }
  7240. memcpy(destination, current_position, sizeof(destination));
  7241. SERIAL_ECHOPGM("recover_machine_state_after_power_panic, initial ");
  7242. print_world_coordinates();
  7243. // 2) Initialize the logical to physical coordinate system transformation.
  7244. world2machine_initialize();
  7245. // 3) Restore the mesh bed leveling offsets. This is 2*9=18 bytes, which takes 18*3.4us=52us in worst case.
  7246. mbl.active = false;
  7247. for (int8_t mesh_point = 0; mesh_point < 9; ++ mesh_point) {
  7248. uint8_t ix = mesh_point % MESH_MEAS_NUM_X_POINTS; // from 0 to MESH_NUM_X_POINTS - 1
  7249. uint8_t iy = mesh_point / MESH_MEAS_NUM_X_POINTS;
  7250. // Scale the z value to 10u resolution.
  7251. int16_t v;
  7252. eeprom_read_block(&v, (void*)(EEPROM_UVLO_MESH_BED_LEVELING+2*mesh_point), 2);
  7253. if (v != 0)
  7254. mbl.active = true;
  7255. mbl.z_values[iy][ix] = float(v) * 0.001f;
  7256. }
  7257. if (mbl.active)
  7258. mbl.upsample_3x3();
  7259. // SERIAL_ECHOPGM("recover_machine_state_after_power_panic, initial ");
  7260. // print_mesh_bed_leveling_table();
  7261. // 4) Load the baby stepping value, which is expected to be active at the time of power panic.
  7262. // The baby stepping value is used to reset the physical Z axis when rehoming the Z axis.
  7263. babystep_load();
  7264. // 5) Set the physical positions from the logical positions using the world2machine transformation and the active bed leveling.
  7265. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  7266. // 6) Power up the motors, mark their positions as known.
  7267. //FIXME Verfiy, whether the X and Y axes should be powered up here, as they will later be re-homed anyway.
  7268. axis_known_position[X_AXIS] = true; enable_x();
  7269. axis_known_position[Y_AXIS] = true; enable_y();
  7270. axis_known_position[Z_AXIS] = true; enable_z();
  7271. SERIAL_ECHOPGM("recover_machine_state_after_power_panic, initial ");
  7272. print_physical_coordinates();
  7273. // 7) Recover the target temperatures.
  7274. target_temperature[active_extruder] = eeprom_read_byte((uint8_t*)EEPROM_UVLO_TARGET_HOTEND);
  7275. target_temperature_bed = eeprom_read_byte((uint8_t*)EEPROM_UVLO_TARGET_BED);
  7276. }
  7277. void restore_print_from_eeprom() {
  7278. float x_rec, y_rec, z_pos;
  7279. int feedrate_rec;
  7280. uint8_t fan_speed_rec;
  7281. char cmd[30];
  7282. char* c;
  7283. char filename[13];
  7284. uint8_t depth = 0;
  7285. char dir_name[9];
  7286. fan_speed_rec = eeprom_read_byte((uint8_t*)EEPROM_UVLO_FAN_SPEED);
  7287. EEPROM_read_B(EEPROM_UVLO_FEEDRATE, &feedrate_rec);
  7288. SERIAL_ECHOPGM("Feedrate:");
  7289. MYSERIAL.println(feedrate_rec);
  7290. depth = eeprom_read_byte((uint8_t*)EEPROM_DIR_DEPTH);
  7291. MYSERIAL.println(int(depth));
  7292. for (int i = 0; i < depth; i++) {
  7293. for (int j = 0; j < 8; j++) {
  7294. dir_name[j] = eeprom_read_byte((uint8_t*)EEPROM_DIRS + j + 8 * i);
  7295. }
  7296. dir_name[8] = '\0';
  7297. MYSERIAL.println(dir_name);
  7298. card.chdir(dir_name);
  7299. }
  7300. for (int i = 0; i < 8; i++) {
  7301. filename[i] = eeprom_read_byte((uint8_t*)EEPROM_FILENAME + i);
  7302. }
  7303. filename[8] = '\0';
  7304. MYSERIAL.print(filename);
  7305. strcat_P(filename, PSTR(".gco"));
  7306. sprintf_P(cmd, PSTR("M23 %s"), filename);
  7307. for (c = &cmd[4]; *c; c++)
  7308. *c = tolower(*c);
  7309. enquecommand(cmd);
  7310. uint32_t position = eeprom_read_dword((uint32_t*)(EEPROM_FILE_POSITION));
  7311. SERIAL_ECHOPGM("Position read from eeprom:");
  7312. MYSERIAL.println(position);
  7313. // E axis relative mode.
  7314. enquecommand_P(PSTR("M83"));
  7315. // Move to the XY print position in logical coordinates, where the print has been killed.
  7316. strcpy_P(cmd, PSTR("G1 X")); strcat(cmd, ftostr32(eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 0))));
  7317. strcat_P(cmd, PSTR(" Y")); strcat(cmd, ftostr32(eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 4))));
  7318. strcat_P(cmd, PSTR(" F2000"));
  7319. enquecommand(cmd);
  7320. // Move the Z axis down to the print, in logical coordinates.
  7321. strcpy_P(cmd, PSTR("G1 Z")); strcat(cmd, ftostr32(eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION_Z))));
  7322. enquecommand(cmd);
  7323. // Unretract.
  7324. enquecommand_P(PSTR("G1 E" STRINGIFY(2*DEFAULT_RETRACTION)" F480"));
  7325. // Set the feedrate saved at the power panic.
  7326. sprintf_P(cmd, PSTR("G1 F%d"), feedrate_rec);
  7327. enquecommand(cmd);
  7328. if (eeprom_read_byte((uint8_t*)EEPROM_UVLO_E_ABS))
  7329. {
  7330. float extruder_abs_pos = eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION_E));
  7331. enquecommand_P(PSTR("M82")); //E axis abslute mode
  7332. }
  7333. // Set the fan speed saved at the power panic.
  7334. strcpy_P(cmd, PSTR("M106 S"));
  7335. strcat(cmd, itostr3(int(fan_speed_rec)));
  7336. enquecommand(cmd);
  7337. // Set a position in the file.
  7338. sprintf_P(cmd, PSTR("M26 S%lu"), position);
  7339. enquecommand(cmd);
  7340. // Start SD print.
  7341. enquecommand_P(PSTR("M24"));
  7342. }
  7343. #endif //UVLO_SUPPORT
  7344. ////////////////////////////////////////////////////////////////////////////////
  7345. // new save/restore printing
  7346. //extern uint32_t sdpos_atomic;
  7347. bool saved_printing = false;
  7348. uint32_t saved_sdpos = 0;
  7349. float saved_pos[4] = {0, 0, 0, 0};
  7350. // Feedrate hopefully derived from an active block of the planner at the time the print has been canceled, in mm/min.
  7351. float saved_feedrate2 = 0;
  7352. uint8_t saved_active_extruder = 0;
  7353. bool saved_extruder_under_pressure = false;
  7354. void stop_and_save_print_to_ram(float z_move, float e_move)
  7355. {
  7356. if (saved_printing) return;
  7357. cli();
  7358. unsigned char nplanner_blocks = number_of_blocks();
  7359. saved_sdpos = sdpos_atomic; //atomic sd position of last command added in queue
  7360. uint16_t sdlen_planner = planner_calc_sd_length(); //length of sd commands in planner
  7361. saved_sdpos -= sdlen_planner;
  7362. uint16_t sdlen_cmdqueue = cmdqueue_calc_sd_length(); //length of sd commands in cmdqueue
  7363. saved_sdpos -= sdlen_cmdqueue;
  7364. #if 0
  7365. SERIAL_ECHOPGM("SDPOS_ATOMIC="); MYSERIAL.println(sdpos_atomic, DEC);
  7366. SERIAL_ECHOPGM("SDPOS="); MYSERIAL.println(card.get_sdpos(), DEC);
  7367. SERIAL_ECHOPGM("SDLEN_PLAN="); MYSERIAL.println(sdlen_planner, DEC);
  7368. SERIAL_ECHOPGM("SDLEN_CMDQ="); MYSERIAL.println(sdlen_cmdqueue, DEC);
  7369. SERIAL_ECHOPGM("PLANNERBLOCKS="); MYSERIAL.println(int(nplanner_blocks), DEC);
  7370. SERIAL_ECHOPGM("SDSAVED="); MYSERIAL.println(saved_sdpos, DEC);
  7371. SERIAL_ECHOPGM("SDFILELEN="); MYSERIAL.println(card.fileSize(), DEC);
  7372. {
  7373. card.setIndex(saved_sdpos);
  7374. SERIAL_ECHOLNPGM("Content of planner buffer: ");
  7375. for (unsigned int idx = 0; idx < sdlen_planner; ++ idx)
  7376. MYSERIAL.print(char(card.get()));
  7377. SERIAL_ECHOLNPGM("Content of command buffer: ");
  7378. for (unsigned int idx = 0; idx < sdlen_cmdqueue; ++ idx)
  7379. MYSERIAL.print(char(card.get()));
  7380. SERIAL_ECHOLNPGM("End of command buffer");
  7381. }
  7382. {
  7383. // Print the content of the planner buffer, line by line:
  7384. card.setIndex(saved_sdpos);
  7385. int8_t iline = 0;
  7386. for (unsigned char idx = block_buffer_tail; idx != block_buffer_head; idx = (idx + 1) & (BLOCK_BUFFER_SIZE - 1), ++ iline) {
  7387. SERIAL_ECHOPGM("Planner line (from file): ");
  7388. MYSERIAL.print(int(iline), DEC);
  7389. SERIAL_ECHOPGM(", length: ");
  7390. MYSERIAL.print(block_buffer[idx].sdlen, DEC);
  7391. SERIAL_ECHOPGM(", steps: (");
  7392. MYSERIAL.print(block_buffer[idx].steps_x, DEC);
  7393. SERIAL_ECHOPGM(",");
  7394. MYSERIAL.print(block_buffer[idx].steps_y, DEC);
  7395. SERIAL_ECHOPGM(",");
  7396. MYSERIAL.print(block_buffer[idx].steps_z, DEC);
  7397. SERIAL_ECHOPGM(",");
  7398. MYSERIAL.print(block_buffer[idx].steps_e, DEC);
  7399. SERIAL_ECHOPGM("), events: ");
  7400. MYSERIAL.println(block_buffer[idx].step_event_count, DEC);
  7401. for (int len = block_buffer[idx].sdlen; len > 0; -- len)
  7402. MYSERIAL.print(char(card.get()));
  7403. }
  7404. }
  7405. {
  7406. // Print the content of the command buffer, line by line:
  7407. int8_t iline = 0;
  7408. union {
  7409. struct {
  7410. char lo;
  7411. char hi;
  7412. } lohi;
  7413. uint16_t value;
  7414. } sdlen_single;
  7415. int _bufindr = bufindr;
  7416. for (int _buflen = buflen; _buflen > 0; ++ iline) {
  7417. if (cmdbuffer[_bufindr] == CMDBUFFER_CURRENT_TYPE_SDCARD) {
  7418. sdlen_single.lohi.lo = cmdbuffer[_bufindr + 1];
  7419. sdlen_single.lohi.hi = cmdbuffer[_bufindr + 2];
  7420. }
  7421. SERIAL_ECHOPGM("Buffer line (from buffer): ");
  7422. MYSERIAL.print(int(iline), DEC);
  7423. SERIAL_ECHOPGM(", type: ");
  7424. MYSERIAL.print(int(cmdbuffer[_bufindr]), DEC);
  7425. SERIAL_ECHOPGM(", len: ");
  7426. MYSERIAL.println(sdlen_single.value, DEC);
  7427. // Print the content of the buffer line.
  7428. MYSERIAL.println(cmdbuffer + _bufindr + CMDHDRSIZE);
  7429. SERIAL_ECHOPGM("Buffer line (from file): ");
  7430. MYSERIAL.print(int(iline), DEC);
  7431. MYSERIAL.println(int(iline), DEC);
  7432. for (; sdlen_single.value > 0; -- sdlen_single.value)
  7433. MYSERIAL.print(char(card.get()));
  7434. if (-- _buflen == 0)
  7435. break;
  7436. // First skip the current command ID and iterate up to the end of the string.
  7437. for (_bufindr += CMDHDRSIZE; cmdbuffer[_bufindr] != 0; ++ _bufindr) ;
  7438. // Second, skip the end of string null character and iterate until a nonzero command ID is found.
  7439. for (++ _bufindr; _bufindr < sizeof(cmdbuffer) && cmdbuffer[_bufindr] == 0; ++ _bufindr) ;
  7440. // If the end of the buffer was empty,
  7441. if (_bufindr == sizeof(cmdbuffer)) {
  7442. // skip to the start and find the nonzero command.
  7443. for (_bufindr = 0; cmdbuffer[_bufindr] == 0; ++ _bufindr) ;
  7444. }
  7445. }
  7446. }
  7447. #endif
  7448. #if 0
  7449. saved_feedrate2 = feedrate; //save feedrate
  7450. #else
  7451. // Try to deduce the feedrate from the first block of the planner.
  7452. // Speed is in mm/min.
  7453. saved_feedrate2 = blocks_queued() ? (block_buffer[block_buffer_tail].nominal_speed * 60.f) : feedrate;
  7454. #endif
  7455. planner_abort_hard(); //abort printing
  7456. memcpy(saved_pos, current_position, sizeof(saved_pos));
  7457. saved_active_extruder = active_extruder; //save active_extruder
  7458. saved_extruder_under_pressure = extruder_under_pressure; //extruder under pressure flag - currently unused
  7459. cmdqueue_reset(); //empty cmdqueue
  7460. card.sdprinting = false;
  7461. // card.closefile();
  7462. saved_printing = true;
  7463. // We may have missed a stepper timer interrupt. Be safe than sorry, reset the stepper timer before re-enabling interrupts.
  7464. st_reset_timer();
  7465. sei();
  7466. if ((z_move != 0) || (e_move != 0)) { // extruder or z move
  7467. #if 1
  7468. // Rather than calling plan_buffer_line directly, push the move into the command queue,
  7469. char buf[48];
  7470. strcpy_P(buf, PSTR("G1 Z"));
  7471. dtostrf(saved_pos[Z_AXIS] + z_move, 8, 3, buf + strlen(buf));
  7472. strcat_P(buf, PSTR(" E"));
  7473. // Relative extrusion
  7474. dtostrf(e_move, 6, 3, buf + strlen(buf));
  7475. strcat_P(buf, PSTR(" F"));
  7476. dtostrf(homing_feedrate[Z_AXIS], 8, 3, buf + strlen(buf));
  7477. // At this point the command queue is empty.
  7478. enquecommand(buf, false);
  7479. // If this call is invoked from the main Arduino loop() function, let the caller know that the command
  7480. // in the command queue is not the original command, but a new one, so it should not be removed from the queue.
  7481. repeatcommand_front();
  7482. #else
  7483. plan_buffer_line(saved_pos[X_AXIS], saved_pos[Y_AXIS], saved_pos[Z_AXIS] + z_move, saved_pos[E_AXIS] + e_move, homing_feedrate[Z_AXIS], active_extruder);
  7484. st_synchronize(); //wait moving
  7485. memcpy(current_position, saved_pos, sizeof(saved_pos));
  7486. memcpy(destination, current_position, sizeof(destination));
  7487. #endif
  7488. }
  7489. }
  7490. void restore_print_from_ram_and_continue(float e_move)
  7491. {
  7492. if (!saved_printing) return;
  7493. // for (int axis = X_AXIS; axis <= E_AXIS; axis++)
  7494. // current_position[axis] = st_get_position_mm(axis);
  7495. active_extruder = saved_active_extruder; //restore active_extruder
  7496. feedrate = saved_feedrate2; //restore feedrate
  7497. float e = saved_pos[E_AXIS] - e_move;
  7498. plan_set_e_position(e);
  7499. plan_buffer_line(saved_pos[X_AXIS], saved_pos[Y_AXIS], saved_pos[Z_AXIS], saved_pos[E_AXIS], homing_feedrate[Z_AXIS]/13, active_extruder);
  7500. st_synchronize();
  7501. memcpy(current_position, saved_pos, sizeof(saved_pos));
  7502. memcpy(destination, current_position, sizeof(destination));
  7503. card.setIndex(saved_sdpos);
  7504. sdpos_atomic = saved_sdpos;
  7505. card.sdprinting = true;
  7506. saved_printing = false;
  7507. printf_P(PSTR("ok\n")); //dummy response because of octoprint is waiting for this
  7508. }
  7509. void print_world_coordinates()
  7510. {
  7511. SERIAL_ECHOPGM("world coordinates: (");
  7512. MYSERIAL.print(current_position[X_AXIS], 3);
  7513. SERIAL_ECHOPGM(", ");
  7514. MYSERIAL.print(current_position[Y_AXIS], 3);
  7515. SERIAL_ECHOPGM(", ");
  7516. MYSERIAL.print(current_position[Z_AXIS], 3);
  7517. SERIAL_ECHOLNPGM(")");
  7518. }
  7519. void print_physical_coordinates()
  7520. {
  7521. SERIAL_ECHOPGM("physical coordinates: (");
  7522. MYSERIAL.print(st_get_position_mm(X_AXIS), 3);
  7523. SERIAL_ECHOPGM(", ");
  7524. MYSERIAL.print(st_get_position_mm(Y_AXIS), 3);
  7525. SERIAL_ECHOPGM(", ");
  7526. MYSERIAL.print(st_get_position_mm(Z_AXIS), 3);
  7527. SERIAL_ECHOLNPGM(")");
  7528. }
  7529. void print_mesh_bed_leveling_table()
  7530. {
  7531. SERIAL_ECHOPGM("mesh bed leveling: ");
  7532. for (int8_t y = 0; y < MESH_NUM_Y_POINTS; ++ y)
  7533. for (int8_t x = 0; x < MESH_NUM_Y_POINTS; ++ x) {
  7534. MYSERIAL.print(mbl.z_values[y][x], 3);
  7535. SERIAL_ECHOPGM(" ");
  7536. }
  7537. SERIAL_ECHOLNPGM("");
  7538. }
  7539. #define FIL_LOAD_LENGTH 60