Marlin_main.cpp 307 KB

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