Marlin_main.cpp 292 KB

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