Marlin_main.cpp 178 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522152315241525152615271528152915301531153215331534153515361537153815391540154115421543154415451546154715481549155015511552155315541555155615571558155915601561156215631564156515661567156815691570157115721573157415751576157715781579158015811582158315841585158615871588158915901591159215931594159515961597159815991600160116021603160416051606160716081609161016111612161316141615161616171618161916201621162216231624162516261627162816291630163116321633163416351636163716381639164016411642164316441645164616471648164916501651165216531654165516561657165816591660166116621663166416651666166716681669167016711672167316741675167616771678167916801681168216831684168516861687168816891690169116921693169416951696169716981699170017011702170317041705170617071708170917101711171217131714171517161717171817191720172117221723172417251726172717281729173017311732173317341735173617371738173917401741174217431744174517461747174817491750175117521753175417551756175717581759176017611762176317641765176617671768176917701771177217731774177517761777177817791780178117821783178417851786178717881789179017911792179317941795179617971798179918001801180218031804180518061807180818091810181118121813181418151816181718181819182018211822182318241825182618271828182918301831183218331834183518361837183818391840184118421843184418451846184718481849185018511852185318541855185618571858185918601861186218631864186518661867186818691870187118721873187418751876187718781879188018811882188318841885188618871888188918901891189218931894189518961897189818991900190119021903190419051906190719081909191019111912191319141915191619171918191919201921192219231924192519261927192819291930193119321933193419351936193719381939194019411942194319441945194619471948194919501951195219531954195519561957195819591960196119621963196419651966196719681969197019711972197319741975197619771978197919801981198219831984198519861987198819891990199119921993199419951996199719981999200020012002200320042005200620072008200920102011201220132014201520162017201820192020202120222023202420252026202720282029203020312032203320342035203620372038203920402041204220432044204520462047204820492050205120522053205420552056205720582059206020612062206320642065206620672068206920702071207220732074207520762077207820792080208120822083208420852086208720882089209020912092209320942095209620972098209921002101210221032104210521062107210821092110211121122113211421152116211721182119212021212122212321242125212621272128212921302131213221332134213521362137213821392140214121422143214421452146214721482149215021512152215321542155215621572158215921602161216221632164216521662167216821692170217121722173217421752176217721782179218021812182218321842185218621872188218921902191219221932194219521962197219821992200220122022203220422052206220722082209221022112212221322142215221622172218221922202221222222232224222522262227222822292230223122322233223422352236223722382239224022412242224322442245224622472248224922502251225222532254225522562257225822592260226122622263226422652266226722682269227022712272227322742275227622772278227922802281228222832284228522862287228822892290229122922293229422952296229722982299230023012302230323042305230623072308230923102311231223132314231523162317231823192320232123222323232423252326232723282329233023312332233323342335233623372338233923402341234223432344234523462347234823492350235123522353235423552356235723582359236023612362236323642365236623672368236923702371237223732374237523762377237823792380238123822383238423852386238723882389239023912392239323942395239623972398239924002401240224032404240524062407240824092410241124122413241424152416241724182419242024212422242324242425242624272428242924302431243224332434243524362437243824392440244124422443244424452446244724482449245024512452245324542455245624572458245924602461246224632464246524662467246824692470247124722473247424752476247724782479248024812482248324842485248624872488248924902491249224932494249524962497249824992500250125022503250425052506250725082509251025112512251325142515251625172518251925202521252225232524252525262527252825292530253125322533253425352536253725382539254025412542254325442545254625472548254925502551255225532554255525562557255825592560256125622563256425652566256725682569257025712572257325742575257625772578257925802581258225832584258525862587258825892590259125922593259425952596259725982599260026012602260326042605260626072608260926102611261226132614261526162617261826192620262126222623262426252626262726282629263026312632263326342635263626372638263926402641264226432644264526462647264826492650265126522653265426552656265726582659266026612662266326642665266626672668266926702671267226732674267526762677267826792680268126822683268426852686268726882689269026912692269326942695269626972698269927002701270227032704270527062707270827092710271127122713271427152716271727182719272027212722272327242725272627272728272927302731273227332734273527362737273827392740274127422743274427452746274727482749275027512752275327542755275627572758275927602761276227632764276527662767276827692770277127722773277427752776277727782779278027812782278327842785278627872788278927902791279227932794279527962797279827992800280128022803280428052806280728082809281028112812281328142815281628172818281928202821282228232824282528262827282828292830283128322833283428352836283728382839284028412842284328442845284628472848284928502851285228532854285528562857285828592860286128622863286428652866286728682869287028712872287328742875287628772878287928802881288228832884288528862887288828892890289128922893289428952896289728982899290029012902290329042905290629072908290929102911291229132914291529162917291829192920292129222923292429252926292729282929293029312932293329342935293629372938293929402941294229432944294529462947294829492950295129522953295429552956295729582959296029612962296329642965296629672968296929702971297229732974297529762977297829792980298129822983298429852986298729882989299029912992299329942995299629972998299930003001300230033004300530063007300830093010301130123013301430153016301730183019302030213022302330243025302630273028302930303031303230333034303530363037303830393040304130423043304430453046304730483049305030513052305330543055305630573058305930603061306230633064306530663067306830693070307130723073307430753076307730783079308030813082308330843085308630873088308930903091309230933094309530963097309830993100310131023103310431053106310731083109311031113112311331143115311631173118311931203121312231233124312531263127312831293130313131323133313431353136313731383139314031413142314331443145314631473148314931503151315231533154315531563157315831593160316131623163316431653166316731683169317031713172317331743175317631773178317931803181318231833184318531863187318831893190319131923193319431953196319731983199320032013202320332043205320632073208320932103211321232133214321532163217321832193220322132223223322432253226322732283229323032313232323332343235323632373238323932403241324232433244324532463247324832493250325132523253325432553256325732583259326032613262326332643265326632673268326932703271327232733274327532763277327832793280328132823283328432853286328732883289329032913292329332943295329632973298329933003301330233033304330533063307330833093310331133123313331433153316331733183319332033213322332333243325332633273328332933303331333233333334333533363337333833393340334133423343334433453346334733483349335033513352335333543355335633573358335933603361336233633364336533663367336833693370337133723373337433753376337733783379338033813382338333843385338633873388338933903391339233933394339533963397339833993400340134023403340434053406340734083409341034113412341334143415341634173418341934203421342234233424342534263427342834293430343134323433343434353436343734383439344034413442344334443445344634473448344934503451345234533454345534563457345834593460346134623463346434653466346734683469347034713472347334743475347634773478347934803481348234833484348534863487348834893490349134923493349434953496349734983499350035013502350335043505350635073508350935103511351235133514351535163517351835193520352135223523352435253526352735283529353035313532353335343535353635373538353935403541354235433544354535463547354835493550355135523553355435553556355735583559356035613562356335643565356635673568356935703571357235733574357535763577357835793580358135823583358435853586358735883589359035913592359335943595359635973598359936003601360236033604360536063607360836093610361136123613361436153616361736183619362036213622362336243625362636273628362936303631363236333634363536363637363836393640364136423643364436453646364736483649365036513652365336543655365636573658365936603661366236633664366536663667366836693670367136723673367436753676367736783679368036813682368336843685368636873688368936903691369236933694369536963697369836993700370137023703370437053706370737083709371037113712371337143715371637173718371937203721372237233724372537263727372837293730373137323733373437353736373737383739374037413742374337443745374637473748374937503751375237533754375537563757375837593760376137623763376437653766376737683769377037713772377337743775377637773778377937803781378237833784378537863787378837893790379137923793379437953796379737983799380038013802380338043805380638073808380938103811381238133814381538163817381838193820382138223823382438253826382738283829383038313832383338343835383638373838383938403841384238433844384538463847384838493850385138523853385438553856385738583859386038613862386338643865386638673868386938703871387238733874387538763877387838793880388138823883388438853886388738883889389038913892389338943895389638973898389939003901390239033904390539063907390839093910391139123913391439153916391739183919392039213922392339243925392639273928392939303931393239333934393539363937393839393940394139423943394439453946394739483949395039513952395339543955395639573958395939603961396239633964396539663967396839693970397139723973397439753976397739783979398039813982398339843985398639873988398939903991399239933994399539963997399839994000400140024003400440054006400740084009401040114012401340144015401640174018401940204021402240234024402540264027402840294030403140324033403440354036403740384039404040414042404340444045404640474048404940504051405240534054405540564057405840594060406140624063406440654066406740684069407040714072407340744075407640774078407940804081408240834084408540864087408840894090409140924093409440954096409740984099410041014102410341044105410641074108410941104111411241134114411541164117411841194120412141224123412441254126412741284129413041314132413341344135413641374138413941404141414241434144414541464147414841494150415141524153415441554156415741584159416041614162416341644165416641674168416941704171417241734174417541764177417841794180418141824183418441854186418741884189419041914192419341944195419641974198419942004201420242034204420542064207420842094210421142124213421442154216421742184219422042214222422342244225422642274228422942304231423242334234423542364237423842394240424142424243424442454246424742484249425042514252425342544255425642574258425942604261426242634264426542664267426842694270427142724273427442754276427742784279428042814282428342844285428642874288428942904291429242934294429542964297429842994300430143024303430443054306430743084309431043114312431343144315431643174318431943204321432243234324432543264327432843294330433143324333433443354336433743384339434043414342434343444345434643474348434943504351435243534354435543564357435843594360436143624363436443654366436743684369437043714372437343744375437643774378437943804381438243834384438543864387438843894390439143924393439443954396439743984399440044014402440344044405440644074408440944104411441244134414441544164417441844194420442144224423442444254426442744284429443044314432443344344435443644374438443944404441444244434444444544464447444844494450445144524453445444554456445744584459446044614462446344644465446644674468446944704471447244734474447544764477447844794480448144824483448444854486448744884489449044914492449344944495449644974498449945004501450245034504450545064507450845094510451145124513451445154516451745184519452045214522452345244525452645274528452945304531453245334534453545364537453845394540454145424543454445454546454745484549455045514552455345544555455645574558455945604561456245634564456545664567456845694570457145724573457445754576457745784579458045814582458345844585458645874588458945904591459245934594459545964597459845994600460146024603460446054606460746084609461046114612461346144615461646174618461946204621462246234624462546264627462846294630463146324633463446354636463746384639464046414642464346444645464646474648464946504651465246534654465546564657465846594660466146624663466446654666466746684669467046714672467346744675467646774678467946804681468246834684468546864687468846894690469146924693469446954696469746984699470047014702470347044705470647074708470947104711471247134714471547164717471847194720472147224723472447254726472747284729473047314732473347344735473647374738473947404741474247434744474547464747474847494750475147524753475447554756475747584759476047614762476347644765476647674768476947704771477247734774477547764777477847794780478147824783478447854786478747884789479047914792479347944795479647974798479948004801480248034804480548064807480848094810481148124813481448154816481748184819482048214822482348244825482648274828482948304831483248334834483548364837483848394840484148424843484448454846484748484849485048514852485348544855485648574858485948604861486248634864486548664867486848694870487148724873487448754876487748784879488048814882488348844885488648874888488948904891489248934894489548964897489848994900490149024903490449054906490749084909491049114912491349144915491649174918491949204921492249234924492549264927492849294930493149324933493449354936493749384939494049414942494349444945494649474948494949504951495249534954495549564957495849594960496149624963496449654966496749684969497049714972497349744975497649774978497949804981498249834984498549864987498849894990499149924993499449954996499749984999500050015002500350045005500650075008500950105011501250135014501550165017501850195020502150225023502450255026502750285029503050315032503350345035503650375038503950405041504250435044504550465047504850495050505150525053505450555056505750585059506050615062506350645065506650675068506950705071507250735074507550765077507850795080508150825083508450855086508750885089509050915092509350945095509650975098509951005101510251035104510551065107510851095110511151125113511451155116511751185119512051215122512351245125512651275128512951305131513251335134513551365137513851395140514151425143514451455146514751485149515051515152515351545155515651575158515951605161516251635164516551665167516851695170517151725173517451755176517751785179518051815182518351845185518651875188518951905191519251935194
  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 "ultralcd.h"
  35. #include "Configuration_prusa.h"
  36. #include "planner.h"
  37. #include "stepper.h"
  38. #include "temperature.h"
  39. #include "motion_control.h"
  40. #include "cardreader.h"
  41. #include "watchdog.h"
  42. #include "ConfigurationStore.h"
  43. #include "language.h"
  44. #include "pins_arduino.h"
  45. #include "math.h"
  46. #include "util.h"
  47. #ifdef BLINKM
  48. #include "BlinkM.h"
  49. #include "Wire.h"
  50. #endif
  51. #ifdef ULTRALCD
  52. #include "ultralcd.h"
  53. #endif
  54. #if NUM_SERVOS > 0
  55. #include "Servo.h"
  56. #endif
  57. #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
  58. #include <SPI.h>
  59. #endif
  60. #define VERSION_STRING "1.0.2"
  61. #include "ultralcd.h"
  62. // Macros for bit masks
  63. #define BIT(b) (1<<(b))
  64. #define TEST(n,b) (((n)&BIT(b))!=0)
  65. #define SET_BIT(n,b,value) (n) ^= ((-value)^(n)) & (BIT(b))
  66. // look here for descriptions of G-codes: http://linuxcnc.org/handbook/gcode/g-code.html
  67. // http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
  68. //Implemented Codes
  69. //-------------------
  70. // PRUSA CODES
  71. // P F - Returns FW versions
  72. // P R - Returns revision of printer
  73. // G0 -> G1
  74. // G1 - Coordinated Movement X Y Z E
  75. // G2 - CW ARC
  76. // G3 - CCW ARC
  77. // G4 - Dwell S<seconds> or P<milliseconds>
  78. // G10 - retract filament according to settings of M207
  79. // G11 - retract recover filament according to settings of M208
  80. // G28 - Home all Axis
  81. // G29 - Detailed Z-Probe, probes the bed at 3 or more points. Will fail if you haven't homed yet.
  82. // G30 - Single Z Probe, probes bed at current XY location.
  83. // G31 - Dock sled (Z_PROBE_SLED only)
  84. // G32 - Undock sled (Z_PROBE_SLED only)
  85. // G80 - Automatic mesh bed leveling
  86. // G81 - Print bed profile
  87. // G90 - Use Absolute Coordinates
  88. // G91 - Use Relative Coordinates
  89. // G92 - Set current position to coordinates given
  90. // M Codes
  91. // M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled)
  92. // M1 - Same as M0
  93. // M17 - Enable/Power all stepper motors
  94. // M18 - Disable all stepper motors; same as M84
  95. // M20 - List SD card
  96. // M21 - Init SD card
  97. // M22 - Release SD card
  98. // M23 - Select SD file (M23 filename.g)
  99. // M24 - Start/resume SD print
  100. // M25 - Pause SD print
  101. // M26 - Set SD position in bytes (M26 S12345)
  102. // M27 - Report SD print status
  103. // M28 - Start SD write (M28 filename.g)
  104. // M29 - Stop SD write
  105. // M30 - Delete file from SD (M30 filename.g)
  106. // M31 - Output time since last M109 or SD card start to serial
  107. // M32 - Select file and start SD print (Can be used _while_ printing from SD card files):
  108. // syntax "M32 /path/filename#", or "M32 S<startpos bytes> !filename#"
  109. // Call gcode file : "M32 P !filename#" and return to caller file after finishing (similar to #include).
  110. // The '#' is necessary when calling from within sd files, as it stops buffer prereading
  111. // 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.
  112. // M80 - Turn on Power Supply
  113. // M81 - Turn off Power Supply
  114. // M82 - Set E codes absolute (default)
  115. // M83 - Set E codes relative while in Absolute Coordinates (G90) mode
  116. // M84 - Disable steppers until next move,
  117. // or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
  118. // M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
  119. // M92 - Set axis_steps_per_unit - same syntax as G92
  120. // M104 - Set extruder target temp
  121. // M105 - Read current temp
  122. // M106 - Fan on
  123. // M107 - Fan off
  124. // M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating
  125. // Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling
  126. // IF AUTOTEMP is enabled, S<mintemp> B<maxtemp> F<factor>. Exit autotemp by any M109 without F
  127. // M112 - Emergency stop
  128. // M114 - Output current position to serial port
  129. // M115 - Capabilities string
  130. // M117 - display message
  131. // M119 - Output Endstop status to serial port
  132. // M126 - Solenoid Air Valve Open (BariCUDA support by jmil)
  133. // M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil)
  134. // M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil)
  135. // M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil)
  136. // M140 - Set bed target temp
  137. // 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.
  138. // M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating
  139. // Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
  140. // M200 D<millimeters>- set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).
  141. // M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
  142. // M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
  143. // M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
  144. // 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
  145. // 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
  146. // M206 - set additional homing offset
  147. // M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop], stays in mm regardless of M200 setting
  148. // M208 - set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/sec]
  149. // 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.
  150. // M218 - set hotend offset (in mm): T<extruder_number> X<offset_on_X> Y<offset_on_Y>
  151. // M220 S<factor in percent>- set speed factor override percentage
  152. // M221 S<factor in percent>- set extrude factor override percentage
  153. // M226 P<pin number> S<pin state>- Wait until the specified pin reaches the state required
  154. // M240 - Trigger a camera to take a photograph
  155. // M250 - Set LCD contrast C<contrast value> (value 0..63)
  156. // M280 - set servo position absolute. P: servo index, S: angle or microseconds
  157. // M300 - Play beep sound S<frequency Hz> P<duration ms>
  158. // M301 - Set PID parameters P I and D
  159. // M302 - Allow cold extrudes, or set the minimum extrude S<temperature>.
  160. // M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
  161. // M304 - Set bed PID parameters P I and D
  162. // M400 - Finish all moves
  163. // M401 - Lower z-probe if present
  164. // M402 - Raise z-probe if present
  165. // M404 - N<dia in mm> Enter the nominal filament width (3mm, 1.75mm ) or will display nominal filament width without parameters
  166. // M405 - Turn on Filament Sensor extrusion control. Optional D<delay in cm> to set delay in centimeters between sensor and extruder
  167. // M406 - Turn off Filament Sensor extrusion control
  168. // M407 - Displays measured filament diameter
  169. // M500 - stores parameters in EEPROM
  170. // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
  171. // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
  172. // M503 - print the current settings (from memory not from EEPROM)
  173. // M509 - force language selection on next restart
  174. // M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
  175. // M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
  176. // M605 - Set dual x-carriage movement mode: S<mode> [ X<duplication x-offset> R<duplication temp offset> ]
  177. // M907 - Set digital trimpot motor current using axis codes.
  178. // M908 - Control digital trimpot directly.
  179. // M350 - Set microstepping mode.
  180. // M351 - Toggle MS1 MS2 pins directly.
  181. // M928 - Start SD logging (M928 filename.g) - ended by M29
  182. // M999 - Restart after being stopped by error
  183. //Stepper Movement Variables
  184. //===========================================================================
  185. //=============================imported variables============================
  186. //===========================================================================
  187. //===========================================================================
  188. //=============================public variables=============================
  189. //===========================================================================
  190. #ifdef SDSUPPORT
  191. CardReader card;
  192. #endif
  193. union Data
  194. {
  195. byte b[2];
  196. int value;
  197. };
  198. #define BABYSTEP_LOADZ_BY_PLANNER
  199. // Number of baby steps applied
  200. int babystepLoadZ = 0;
  201. float homing_feedrate[] = HOMING_FEEDRATE;
  202. // Currently only the extruder axis may be switched to a relative mode.
  203. // Other axes are always absolute or relative based on the common relative_mode flag.
  204. bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
  205. int feedmultiply=100; //100->1 200->2
  206. int saved_feedmultiply;
  207. int extrudemultiply=100; //100->1 200->2
  208. int extruder_multiply[EXTRUDERS] = {100
  209. #if EXTRUDERS > 1
  210. , 100
  211. #if EXTRUDERS > 2
  212. , 100
  213. #endif
  214. #endif
  215. };
  216. bool is_usb_printing = false;
  217. unsigned int usb_printing_counter;
  218. int lcd_change_fil_state = 0;
  219. int feedmultiplyBckp = 100;
  220. unsigned char lang_selected = 0;
  221. unsigned long total_filament_used;
  222. unsigned int heating_status;
  223. unsigned int heating_status_counter;
  224. bool custom_message;
  225. unsigned int custom_message_type;
  226. unsigned int custom_message_state;
  227. bool volumetric_enabled = false;
  228. float filament_size[EXTRUDERS] = { DEFAULT_NOMINAL_FILAMENT_DIA
  229. #if EXTRUDERS > 1
  230. , DEFAULT_NOMINAL_FILAMENT_DIA
  231. #if EXTRUDERS > 2
  232. , DEFAULT_NOMINAL_FILAMENT_DIA
  233. #endif
  234. #endif
  235. };
  236. float volumetric_multiplier[EXTRUDERS] = {1.0
  237. #if EXTRUDERS > 1
  238. , 1.0
  239. #if EXTRUDERS > 2
  240. , 1.0
  241. #endif
  242. #endif
  243. };
  244. float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 };
  245. float add_homing[3]={0,0,0};
  246. float min_pos[3] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS };
  247. float max_pos[3] = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS };
  248. bool axis_known_position[3] = {false, false, false};
  249. float zprobe_zoffset;
  250. // Extruder offset
  251. #if EXTRUDERS > 1
  252. #define NUM_EXTRUDER_OFFSETS 2 // only in XY plane
  253. float extruder_offset[NUM_EXTRUDER_OFFSETS][EXTRUDERS] = {
  254. #if defined(EXTRUDER_OFFSET_X) && defined(EXTRUDER_OFFSET_Y)
  255. EXTRUDER_OFFSET_X, EXTRUDER_OFFSET_Y
  256. #endif
  257. };
  258. #endif
  259. uint8_t active_extruder = 0;
  260. int fanSpeed=0;
  261. #ifdef FWRETRACT
  262. bool autoretract_enabled=false;
  263. bool retracted[EXTRUDERS]={false
  264. #if EXTRUDERS > 1
  265. , false
  266. #if EXTRUDERS > 2
  267. , false
  268. #endif
  269. #endif
  270. };
  271. bool retracted_swap[EXTRUDERS]={false
  272. #if EXTRUDERS > 1
  273. , false
  274. #if EXTRUDERS > 2
  275. , false
  276. #endif
  277. #endif
  278. };
  279. float retract_length = RETRACT_LENGTH;
  280. float retract_length_swap = RETRACT_LENGTH_SWAP;
  281. float retract_feedrate = RETRACT_FEEDRATE;
  282. float retract_zlift = RETRACT_ZLIFT;
  283. float retract_recover_length = RETRACT_RECOVER_LENGTH;
  284. float retract_recover_length_swap = RETRACT_RECOVER_LENGTH_SWAP;
  285. float retract_recover_feedrate = RETRACT_RECOVER_FEEDRATE;
  286. #endif
  287. #ifdef ULTIPANEL
  288. #ifdef PS_DEFAULT_OFF
  289. bool powersupply = false;
  290. #else
  291. bool powersupply = true;
  292. #endif
  293. #endif
  294. bool cancel_heatup = false ;
  295. #ifdef FILAMENT_SENSOR
  296. //Variables for Filament Sensor input
  297. float filament_width_nominal=DEFAULT_NOMINAL_FILAMENT_DIA; //Set nominal filament width, can be changed with M404
  298. bool filament_sensor=false; //M405 turns on filament_sensor control, M406 turns it off
  299. float filament_width_meas=DEFAULT_MEASURED_FILAMENT_DIA; //Stores the measured filament diameter
  300. signed char measurement_delay[MAX_MEASUREMENT_DELAY+1]; //ring buffer to delay measurement store extruder factor after subtracting 100
  301. int delay_index1=0; //index into ring buffer
  302. int delay_index2=-1; //index into ring buffer - set to -1 on startup to indicate ring buffer needs to be initialized
  303. float delay_dist=0; //delay distance counter
  304. int meas_delay_cm = MEASUREMENT_DELAY_CM; //distance delay setting
  305. #endif
  306. const char errormagic[] PROGMEM = "Error:";
  307. const char echomagic[] PROGMEM = "echo:";
  308. //===========================================================================
  309. //=============================Private Variables=============================
  310. //===========================================================================
  311. const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
  312. float destination[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0};
  313. static float delta[3] = {0.0, 0.0, 0.0};
  314. // For tracing an arc
  315. static float offset[3] = {0.0, 0.0, 0.0};
  316. static bool home_all_axis = true;
  317. static float feedrate = 1500.0, next_feedrate, saved_feedrate;
  318. static long gcode_N, gcode_LastN, Stopped_gcode_LastN = 0;
  319. // Determines Absolute or Relative Coordinates.
  320. // Also there is bool axis_relative_modes[] per axis flag.
  321. static bool relative_mode = false;
  322. // String circular buffer. Commands may be pushed to the buffer from both sides:
  323. // Chained commands will be pushed to the front, interactive (from LCD menu)
  324. // and printing commands (from serial line or from SD card) are pushed to the tail.
  325. // First character of each entry indicates the type of the entry:
  326. #define CMDBUFFER_CURRENT_TYPE_UNKNOWN 0
  327. // Command in cmdbuffer was sent over USB.
  328. #define CMDBUFFER_CURRENT_TYPE_USB 1
  329. // Command in cmdbuffer was read from SDCARD.
  330. #define CMDBUFFER_CURRENT_TYPE_SDCARD 2
  331. // Command in cmdbuffer was generated by the UI.
  332. #define CMDBUFFER_CURRENT_TYPE_UI 3
  333. // Command in cmdbuffer was generated by another G-code.
  334. #define CMDBUFFER_CURRENT_TYPE_CHAINED 4
  335. // How much space to reserve for the chained commands
  336. // of type CMDBUFFER_CURRENT_TYPE_CHAINED,
  337. // which are pushed to the front of the queue?
  338. // Maximum 5 commands of max length 20 + null terminator.
  339. #define CMDBUFFER_RESERVE_FRONT (5*21)
  340. // Reserve BUFSIZE lines of length MAX_CMD_SIZE plus CMDBUFFER_RESERVE_FRONT.
  341. static char cmdbuffer[BUFSIZE * (MAX_CMD_SIZE + 1) + CMDBUFFER_RESERVE_FRONT];
  342. // Head of the circular buffer, where to read.
  343. static int bufindr = 0;
  344. // Tail of the buffer, where to write.
  345. static int bufindw = 0;
  346. // Number of lines in cmdbuffer.
  347. static int buflen = 0;
  348. // Flag for processing the current command inside the main Arduino loop().
  349. // If a new command was pushed to the front of a command buffer while
  350. // processing another command, this replaces the command on the top.
  351. // Therefore don't remove the command from the queue in the loop() function.
  352. static bool cmdbuffer_front_already_processed = false;
  353. // Type of a command, which is to be executed right now.
  354. #define CMDBUFFER_CURRENT_TYPE (cmdbuffer[bufindr])
  355. // String of a command, which is to be executed right now.
  356. #define CMDBUFFER_CURRENT_STRING (cmdbuffer+bufindr+1)
  357. // Enable debugging of the command buffer.
  358. // Debugging information will be sent to serial line.
  359. // #define CMDBUFFER_DEBUG
  360. static int serial_count = 0;
  361. static boolean comment_mode = false;
  362. static char *strchr_pointer; // just a pointer to find chars in the command string like X, Y, Z, E, etc
  363. const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42
  364. //static float tt = 0;
  365. //static float bt = 0;
  366. //Inactivity shutdown variables
  367. static unsigned long previous_millis_cmd = 0;
  368. unsigned long max_inactive_time = 0;
  369. static unsigned long stepper_inactive_time = DEFAULT_STEPPER_DEACTIVE_TIME*1000l;
  370. unsigned long starttime=0;
  371. unsigned long stoptime=0;
  372. unsigned long _usb_timer = 0;
  373. static uint8_t tmp_extruder;
  374. bool Stopped=false;
  375. #if NUM_SERVOS > 0
  376. Servo servos[NUM_SERVOS];
  377. #endif
  378. bool CooldownNoWait = true;
  379. bool target_direction;
  380. //Insert variables if CHDK is defined
  381. #ifdef CHDK
  382. unsigned long chdkHigh = 0;
  383. boolean chdkActive = false;
  384. #endif
  385. //===========================================================================
  386. //=============================Routines======================================
  387. //===========================================================================
  388. void get_arc_coordinates();
  389. bool setTargetedHotend(int code);
  390. void serial_echopair_P(const char *s_P, float v)
  391. { serialprintPGM(s_P); SERIAL_ECHO(v); }
  392. void serial_echopair_P(const char *s_P, double v)
  393. { serialprintPGM(s_P); SERIAL_ECHO(v); }
  394. void serial_echopair_P(const char *s_P, unsigned long v)
  395. { serialprintPGM(s_P); SERIAL_ECHO(v); }
  396. #ifdef SDSUPPORT
  397. #include "SdFatUtil.h"
  398. int freeMemory() { return SdFatUtil::FreeRam(); }
  399. #else
  400. extern "C" {
  401. extern unsigned int __bss_end;
  402. extern unsigned int __heap_start;
  403. extern void *__brkval;
  404. int freeMemory() {
  405. int free_memory;
  406. if ((int)__brkval == 0)
  407. free_memory = ((int)&free_memory) - ((int)&__bss_end);
  408. else
  409. free_memory = ((int)&free_memory) - ((int)__brkval);
  410. return free_memory;
  411. }
  412. }
  413. #endif //!SDSUPPORT
  414. // Pop the currently processed command from the queue.
  415. // It is expected, that there is at least one command in the queue.
  416. void cmdqueue_pop_front()
  417. {
  418. if (buflen > 0) {
  419. #ifdef CMDBUFFER_DEBUG
  420. SERIAL_ECHOPGM("Dequeing ");
  421. SERIAL_ECHO(cmdbuffer+bufindr+1);
  422. SERIAL_ECHOLNPGM("");
  423. SERIAL_ECHOPGM("Old indices: buflen ");
  424. SERIAL_ECHO(buflen);
  425. SERIAL_ECHOPGM(", bufindr ");
  426. SERIAL_ECHO(bufindr);
  427. SERIAL_ECHOPGM(", bufindw ");
  428. SERIAL_ECHO(bufindw);
  429. SERIAL_ECHOPGM(", serial_count ");
  430. SERIAL_ECHO(serial_count);
  431. SERIAL_ECHOPGM(", bufsize ");
  432. SERIAL_ECHO(sizeof(cmdbuffer));
  433. SERIAL_ECHOLNPGM("");
  434. #endif /* CMDBUFFER_DEBUG */
  435. if (-- buflen == 0) {
  436. // Empty buffer.
  437. if (serial_count == 0)
  438. // No serial communication is pending. Reset both pointers to zero.
  439. bufindw = 0;
  440. bufindr = bufindw;
  441. } else {
  442. // There is at least one ready line in the buffer.
  443. // First skip the current command ID and iterate up to the end of the string.
  444. for (++ bufindr; cmdbuffer[bufindr] != 0; ++ bufindr) ;
  445. // Second, skip the end of string null character and iterate until a nonzero command ID is found.
  446. for (++ bufindr; bufindr < sizeof(cmdbuffer) && cmdbuffer[bufindr] == 0; ++ bufindr) ;
  447. // If the end of the buffer was empty,
  448. if (bufindr == sizeof(cmdbuffer)) {
  449. // skip to the start and find the nonzero command.
  450. for (bufindr = 0; cmdbuffer[bufindr] == 0; ++ bufindr) ;
  451. }
  452. #ifdef CMDBUFFER_DEBUG
  453. SERIAL_ECHOPGM("New indices: buflen ");
  454. SERIAL_ECHO(buflen);
  455. SERIAL_ECHOPGM(", bufindr ");
  456. SERIAL_ECHO(bufindr);
  457. SERIAL_ECHOPGM(", bufindw ");
  458. SERIAL_ECHO(bufindw);
  459. SERIAL_ECHOPGM(", serial_count ");
  460. SERIAL_ECHO(serial_count);
  461. SERIAL_ECHOPGM(" new command on the top: ");
  462. SERIAL_ECHO(cmdbuffer+bufindr+1);
  463. SERIAL_ECHOLNPGM("");
  464. #endif /* CMDBUFFER_DEBUG */
  465. }
  466. }
  467. }
  468. // How long a string could be pushed to the front of the command queue?
  469. // If yes, adjust bufindr to the new position, where the new command could be enqued.
  470. // len_asked does not contain the zero terminator size.
  471. bool cmdqueue_could_enqueue_front(int len_asked)
  472. {
  473. // MAX_CMD_SIZE has to accommodate the zero terminator.
  474. if (len_asked >= MAX_CMD_SIZE)
  475. return false;
  476. // Remove the currently processed command from the queue.
  477. if (! cmdbuffer_front_already_processed) {
  478. cmdqueue_pop_front();
  479. cmdbuffer_front_already_processed = true;
  480. }
  481. if (bufindr == bufindw && buflen > 0)
  482. // Full buffer.
  483. return false;
  484. // Adjust the end of the write buffer based on whether a partial line is in the receive buffer.
  485. int endw = (serial_count > 0) ? (bufindw + MAX_CMD_SIZE + 1) : bufindw;
  486. if (bufindw < bufindr) {
  487. int bufindr_new = bufindr - len_asked - 2;
  488. // Simple case. There is a contiguous space between the write buffer and the read buffer.
  489. if (endw <= bufindr_new) {
  490. bufindr = bufindr_new;
  491. return true;
  492. }
  493. } else {
  494. // Otherwise the free space is split between the start and end.
  495. if (len_asked + 2 <= bufindr) {
  496. // Could fit at the start.
  497. bufindr -= len_asked + 2;
  498. return true;
  499. }
  500. int bufindr_new = sizeof(cmdbuffer) - len_asked - 2;
  501. if (endw <= bufindr_new) {
  502. memset(cmdbuffer, 0, bufindr);
  503. bufindr = bufindr_new;
  504. return true;
  505. }
  506. }
  507. return false;
  508. }
  509. // Could one enqueue a command of lenthg len_asked into the buffer,
  510. // while leaving CMDBUFFER_RESERVE_FRONT at the start?
  511. // If yes, adjust bufindw to the new position, where the new command could be enqued.
  512. // len_asked does not contain the zero terminator size.
  513. bool cmdqueue_could_enqueue_back(int len_asked)
  514. {
  515. // MAX_CMD_SIZE has to accommodate the zero terminator.
  516. if (len_asked >= MAX_CMD_SIZE)
  517. return false;
  518. if (bufindr == bufindw && buflen > 0)
  519. // Full buffer.
  520. return false;
  521. if (serial_count > 0) {
  522. // If there is some data stored starting at bufindw, len_asked is certainly smaller than
  523. // the allocated data buffer. Try to reserve a new buffer and to move the already received
  524. // serial data.
  525. // How much memory to reserve for the commands pushed to the front?
  526. // End of the queue, when pushing to the end.
  527. int endw = bufindw + len_asked + 2;
  528. if (bufindw < bufindr)
  529. // Simple case. There is a contiguous space between the write buffer and the read buffer.
  530. return endw + CMDBUFFER_RESERVE_FRONT <= bufindr;
  531. // Otherwise the free space is split between the start and end.
  532. if (// Could one fit to the end, including the reserve?
  533. endw + CMDBUFFER_RESERVE_FRONT <= sizeof(cmdbuffer) ||
  534. // Could one fit to the end, and the reserve to the start?
  535. (endw <= sizeof(cmdbuffer) && CMDBUFFER_RESERVE_FRONT <= bufindr))
  536. return true;
  537. // Could one fit both to the start?
  538. if (len_asked + 2 + CMDBUFFER_RESERVE_FRONT <= bufindr) {
  539. // Mark the rest of the buffer as used.
  540. memset(cmdbuffer+bufindw, 0, sizeof(cmdbuffer)-bufindw);
  541. // and point to the start.
  542. bufindw = 0;
  543. return true;
  544. }
  545. } else {
  546. // How much memory to reserve for the commands pushed to the front?
  547. // End of the queue, when pushing to the end.
  548. int endw = bufindw + len_asked + 2;
  549. if (bufindw < bufindr)
  550. // Simple case. There is a contiguous space between the write buffer and the read buffer.
  551. return endw + CMDBUFFER_RESERVE_FRONT <= bufindr;
  552. // Otherwise the free space is split between the start and end.
  553. if (// Could one fit to the end, including the reserve?
  554. endw + CMDBUFFER_RESERVE_FRONT <= sizeof(cmdbuffer) ||
  555. // Could one fit to the end, and the reserve to the start?
  556. (endw <= sizeof(cmdbuffer) && CMDBUFFER_RESERVE_FRONT <= bufindr))
  557. return true;
  558. // Could one fit both to the start?
  559. if (len_asked + 2 + CMDBUFFER_RESERVE_FRONT <= bufindr) {
  560. // Mark the rest of the buffer as used.
  561. memset(cmdbuffer+bufindw, 0, sizeof(cmdbuffer)-bufindw);
  562. // and point to the start.
  563. bufindw = 0;
  564. return true;
  565. }
  566. }
  567. return false;
  568. }
  569. #ifdef CMDBUFFER_DEBUG
  570. static void cmdqueue_dump_to_serial_single_line(int nr, const char *p)
  571. {
  572. SERIAL_ECHOPGM("Entry nr: ");
  573. SERIAL_ECHO(nr);
  574. SERIAL_ECHOPGM(", type: ");
  575. SERIAL_ECHO(int(*p));
  576. SERIAL_ECHOPGM(", cmd: ");
  577. SERIAL_ECHO(p+1);
  578. SERIAL_ECHOLNPGM("");
  579. }
  580. static void cmdqueue_dump_to_serial()
  581. {
  582. if (buflen == 0) {
  583. SERIAL_ECHOLNPGM("The command buffer is empty.");
  584. } else {
  585. SERIAL_ECHOPGM("Content of the buffer: entries ");
  586. SERIAL_ECHO(buflen);
  587. SERIAL_ECHOPGM(", indr ");
  588. SERIAL_ECHO(bufindr);
  589. SERIAL_ECHOPGM(", indw ");
  590. SERIAL_ECHO(bufindw);
  591. SERIAL_ECHOLNPGM("");
  592. int nr = 0;
  593. if (bufindr < bufindw) {
  594. for (const char *p = cmdbuffer + bufindr; p < cmdbuffer + bufindw; ++ nr) {
  595. cmdqueue_dump_to_serial_single_line(nr, p);
  596. // Skip the command.
  597. for (++p; *p != 0; ++ p);
  598. // Skip the gaps.
  599. for (++p; p < cmdbuffer + bufindw && *p == 0; ++ p);
  600. }
  601. } else {
  602. for (const char *p = cmdbuffer + bufindr; p < cmdbuffer + sizeof(cmdbuffer); ++ nr) {
  603. cmdqueue_dump_to_serial_single_line(nr, p);
  604. // Skip the command.
  605. for (++p; *p != 0; ++ p);
  606. // Skip the gaps.
  607. for (++p; p < cmdbuffer + sizeof(cmdbuffer) && *p == 0; ++ p);
  608. }
  609. for (const char *p = cmdbuffer; p < cmdbuffer + bufindw; ++ nr) {
  610. cmdqueue_dump_to_serial_single_line(nr, p);
  611. // Skip the command.
  612. for (++p; *p != 0; ++ p);
  613. // Skip the gaps.
  614. for (++p; p < cmdbuffer + bufindw && *p == 0; ++ p);
  615. }
  616. }
  617. SERIAL_ECHOLNPGM("End of the buffer.");
  618. }
  619. }
  620. #endif /* CMDBUFFER_DEBUG */
  621. //adds an command to the main command buffer
  622. //thats really done in a non-safe way.
  623. //needs overworking someday
  624. // Currently the maximum length of a command piped through this function is around 20 characters
  625. void enquecommand(const char *cmd, bool from_progmem)
  626. {
  627. int len = from_progmem ? strlen_P(cmd) : strlen(cmd);
  628. // Does cmd fit the queue while leaving sufficient space at the front for the chained commands?
  629. // If it fits, it may move bufindw, so it points to a contiguous buffer, which fits cmd.
  630. if (cmdqueue_could_enqueue_back(len)) {
  631. // This is dangerous if a mixing of serial and this happens
  632. // This may easily be tested: If serial_count > 0, we have a problem.
  633. cmdbuffer[bufindw] = CMDBUFFER_CURRENT_TYPE_UI;
  634. if (from_progmem)
  635. strcpy_P(cmdbuffer + bufindw + 1, cmd);
  636. else
  637. strcpy(cmdbuffer + bufindw + 1, cmd);
  638. SERIAL_ECHO_START;
  639. SERIAL_ECHORPGM(MSG_Enqueing);
  640. SERIAL_ECHO(cmdbuffer + bufindw + 1);
  641. SERIAL_ECHOLNPGM("\"");
  642. bufindw += len + 2;
  643. if (bufindw == sizeof(cmdbuffer))
  644. bufindw = 0;
  645. ++ buflen;
  646. #ifdef CMDBUFFER_DEBUG
  647. cmdqueue_dump_to_serial();
  648. #endif /* CMDBUFFER_DEBUG */
  649. } else {
  650. SERIAL_ERROR_START;
  651. SERIAL_ECHORPGM(MSG_Enqueing);
  652. if (from_progmem)
  653. SERIAL_PROTOCOLRPGM(cmd);
  654. else
  655. SERIAL_ECHO(cmd);
  656. SERIAL_ECHOLNPGM("\" failed: Buffer full!");
  657. #ifdef CMDBUFFER_DEBUG
  658. cmdqueue_dump_to_serial();
  659. #endif /* CMDBUFFER_DEBUG */
  660. }
  661. }
  662. void enquecommand_front(const char *cmd, bool from_progmem)
  663. {
  664. int len = from_progmem ? strlen_P(cmd) : strlen(cmd);
  665. // Does cmd fit the queue? This call shall move bufindr, so the command may be copied.
  666. if (cmdqueue_could_enqueue_front(len)) {
  667. cmdbuffer[bufindr] = CMDBUFFER_CURRENT_TYPE_UI;
  668. if (from_progmem)
  669. strcpy_P(cmdbuffer + bufindr + 1, cmd);
  670. else
  671. strcpy(cmdbuffer + bufindr + 1, cmd);
  672. ++ buflen;
  673. SERIAL_ECHO_START;
  674. SERIAL_ECHOPGM("Enqueing to the front: \"");
  675. SERIAL_ECHO(cmdbuffer + bufindr + 1);
  676. SERIAL_ECHOLNPGM("\"");
  677. #ifdef CMDBUFFER_DEBUG
  678. cmdqueue_dump_to_serial();
  679. #endif /* CMDBUFFER_DEBUG */
  680. } else {
  681. SERIAL_ERROR_START;
  682. SERIAL_ECHOPGM("Enqueing to the front: \"");
  683. if (from_progmem)
  684. SERIAL_PROTOCOLRPGM(cmd);
  685. else
  686. SERIAL_ECHO(cmd);
  687. SERIAL_ECHOLNPGM("\" failed: Buffer full!");
  688. #ifdef CMDBUFFER_DEBUG
  689. cmdqueue_dump_to_serial();
  690. #endif /* CMDBUFFER_DEBUG */
  691. }
  692. }
  693. // Mark the command at the top of the command queue as new.
  694. // Therefore it will not be removed from the queue.
  695. void repeatcommand_front()
  696. {
  697. cmdbuffer_front_already_processed = true;
  698. }
  699. void setup_killpin()
  700. {
  701. #if defined(KILL_PIN) && KILL_PIN > -1
  702. SET_INPUT(KILL_PIN);
  703. WRITE(KILL_PIN,HIGH);
  704. #endif
  705. }
  706. // Set home pin
  707. void setup_homepin(void)
  708. {
  709. #if defined(HOME_PIN) && HOME_PIN > -1
  710. SET_INPUT(HOME_PIN);
  711. WRITE(HOME_PIN,HIGH);
  712. #endif
  713. }
  714. void setup_photpin()
  715. {
  716. #if defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1
  717. SET_OUTPUT(PHOTOGRAPH_PIN);
  718. WRITE(PHOTOGRAPH_PIN, LOW);
  719. #endif
  720. }
  721. void setup_powerhold()
  722. {
  723. #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
  724. SET_OUTPUT(SUICIDE_PIN);
  725. WRITE(SUICIDE_PIN, HIGH);
  726. #endif
  727. #if defined(PS_ON_PIN) && PS_ON_PIN > -1
  728. SET_OUTPUT(PS_ON_PIN);
  729. #if defined(PS_DEFAULT_OFF)
  730. WRITE(PS_ON_PIN, PS_ON_ASLEEP);
  731. #else
  732. WRITE(PS_ON_PIN, PS_ON_AWAKE);
  733. #endif
  734. #endif
  735. }
  736. void suicide()
  737. {
  738. #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
  739. SET_OUTPUT(SUICIDE_PIN);
  740. WRITE(SUICIDE_PIN, LOW);
  741. #endif
  742. }
  743. void servo_init()
  744. {
  745. #if (NUM_SERVOS >= 1) && defined(SERVO0_PIN) && (SERVO0_PIN > -1)
  746. servos[0].attach(SERVO0_PIN);
  747. #endif
  748. #if (NUM_SERVOS >= 2) && defined(SERVO1_PIN) && (SERVO1_PIN > -1)
  749. servos[1].attach(SERVO1_PIN);
  750. #endif
  751. #if (NUM_SERVOS >= 3) && defined(SERVO2_PIN) && (SERVO2_PIN > -1)
  752. servos[2].attach(SERVO2_PIN);
  753. #endif
  754. #if (NUM_SERVOS >= 4) && defined(SERVO3_PIN) && (SERVO3_PIN > -1)
  755. servos[3].attach(SERVO3_PIN);
  756. #endif
  757. #if (NUM_SERVOS >= 5)
  758. #error "TODO: enter initalisation code for more servos"
  759. #endif
  760. }
  761. static void lcd_language_menu();
  762. #ifdef MESH_BED_LEVELING
  763. enum MeshLevelingState { MeshReport, MeshStart, MeshNext, MeshSet };
  764. #endif
  765. // "Setup" function is called by the Arduino framework on startup.
  766. // Before startup, the Timers-functions (PWM)/Analog RW and HardwareSerial provided by the Arduino-code
  767. // are initialized by the main() routine provided by the Arduino framework.
  768. void setup()
  769. {
  770. setup_killpin();
  771. setup_powerhold();
  772. MYSERIAL.begin(BAUDRATE);
  773. SERIAL_PROTOCOLLNPGM("start");
  774. SERIAL_ECHO_START;
  775. #if 0
  776. SERIAL_ECHOLN("Reading eeprom from 0 to 100: start");
  777. for (int i = 0; i < 4096; ++ i) {
  778. int b = eeprom_read_byte((unsigned char*)i);
  779. if (b != 255) {
  780. SERIAL_ECHO(i);
  781. SERIAL_ECHO(":");
  782. SERIAL_ECHO(b);
  783. SERIAL_ECHOLN("");
  784. }
  785. }
  786. SERIAL_ECHOLN("Reading eeprom from 0 to 100: done");
  787. #endif
  788. // Check startup - does nothing if bootloader sets MCUSR to 0
  789. byte mcu = MCUSR;
  790. if(mcu & 1) SERIAL_ECHOLNRPGM(MSG_POWERUP);
  791. if(mcu & 2) SERIAL_ECHOLNRPGM(MSG_EXTERNAL_RESET);
  792. if(mcu & 4) SERIAL_ECHOLNRPGM(MSG_BROWNOUT_RESET);
  793. if(mcu & 8) SERIAL_ECHOLNRPGM(MSG_WATCHDOG_RESET);
  794. if(mcu & 32) SERIAL_ECHOLNRPGM(MSG_SOFTWARE_RESET);
  795. MCUSR=0;
  796. //SERIAL_ECHORPGM(MSG_MARLIN);
  797. //SERIAL_ECHOLNRPGM(VERSION_STRING);
  798. #ifdef STRING_VERSION_CONFIG_H
  799. #ifdef STRING_CONFIG_H_AUTHOR
  800. SERIAL_ECHO_START;
  801. SERIAL_ECHORPGM(MSG_CONFIGURATION_VER);
  802. SERIAL_ECHOPGM(STRING_VERSION_CONFIG_H);
  803. SERIAL_ECHORPGM(MSG_AUTHOR);
  804. SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR);
  805. SERIAL_ECHOPGM("Compiled: ");
  806. SERIAL_ECHOLNPGM(__DATE__);
  807. #endif
  808. #endif
  809. SERIAL_ECHO_START;
  810. SERIAL_ECHORPGM(MSG_FREE_MEMORY);
  811. SERIAL_ECHO(freeMemory());
  812. SERIAL_ECHORPGM(MSG_PLANNER_BUFFER_BYTES);
  813. SERIAL_ECHOLN((int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
  814. // loads data from EEPROM if available else uses defaults (and resets step acceleration rate)
  815. Config_RetrieveSettings();
  816. tp_init(); // Initialize temperature loop
  817. plan_init(); // Initialize planner;
  818. watchdog_init();
  819. st_init(); // Initialize stepper, this enables interrupts!
  820. setup_photpin();
  821. servo_init();
  822. // Reset the machine correction matrix.
  823. // It does not make sense to load the correction matrix until the machine is homed.
  824. world2machine_reset();
  825. lcd_init();
  826. if (!READ(BTN_ENC))
  827. {
  828. _delay_ms(1000);
  829. if (!READ(BTN_ENC))
  830. {
  831. SET_OUTPUT(BEEPER);
  832. WRITE(BEEPER, HIGH);
  833. lcd_force_language_selection();
  834. farm_no = 0;
  835. EEPROM_save_B(EEPROM_FARM_MODE, &farm_no);
  836. farm_mode = false;
  837. while (!READ(BTN_ENC));
  838. WRITE(BEEPER, LOW);
  839. #ifdef MESH_BED_LEVELING
  840. _delay_ms(2000);
  841. if (!READ(BTN_ENC))
  842. {
  843. WRITE(BEEPER, HIGH);
  844. _delay_ms(100);
  845. WRITE(BEEPER, LOW);
  846. _delay_ms(200);
  847. WRITE(BEEPER, HIGH);
  848. _delay_ms(100);
  849. WRITE(BEEPER, LOW);
  850. int _z = 0;
  851. eeprom_write_byte((unsigned char*)EEPROM_BABYSTEP_Z_SET, 0x01);
  852. EEPROM_save_B(EEPROM_BABYSTEP_X, &_z);
  853. EEPROM_save_B(EEPROM_BABYSTEP_Y, &_z);
  854. EEPROM_save_B(EEPROM_BABYSTEP_Z, &_z);
  855. }
  856. else
  857. {
  858. WRITE(BEEPER, HIGH);
  859. _delay_ms(100);
  860. WRITE(BEEPER, LOW);
  861. }
  862. #endif // mesh
  863. }
  864. }
  865. else
  866. {
  867. _delay_ms(1000); // wait 1sec to display the splash screen
  868. }
  869. #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
  870. SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
  871. #endif
  872. #ifdef DIGIPOT_I2C
  873. digipot_i2c_init();
  874. #endif
  875. setup_homepin();
  876. #if defined(Z_AXIS_ALWAYS_ON)
  877. enable_z();
  878. #endif
  879. EEPROM_read_B(EEPROM_FARM_MODE, &farm_no);
  880. if (farm_no > 0)
  881. {
  882. farm_mode = true;
  883. farm_no = farm_no;
  884. prusa_statistics(8);
  885. }
  886. else
  887. {
  888. farm_mode = false;
  889. farm_no = 0;
  890. }
  891. // In the future, somewhere here would one compare the current firmware version against the firmware version stored in the EEPROM.
  892. // If they differ, an update procedure may need to be performed. At the end of this block, the current firmware version
  893. // is being written into the EEPROM, so the update procedure will be triggered only once.
  894. if (eeprom_read_byte((uint8_t*)EEPROM_BABYSTEP_Z_SET) == 0x0ff) {
  895. // Reset the babystepping values, so the printer will not move the Z axis up when the babystepping is enabled.
  896. // eeprom_update_byte((uint8_t*)EEPROM_BABYSTEP_X, 0x0ff);
  897. // eeprom_update_byte((uint8_t*)EEPROM_BABYSTEP_Y, 0x0ff);
  898. eeprom_update_byte((uint8_t*)EEPROM_BABYSTEP_Z, 0x0ff);
  899. // Get the selected laugnage index before display update.
  900. lang_selected = eeprom_read_byte((uint8_t*)EEPROM_LANG);
  901. if (lang_selected >= LANG_NUM)
  902. lang_selected = 1;
  903. // Show the message.
  904. lcd_show_fullscreen_message_and_wait_P(MSG_BABYSTEP_Z_NOT_SET);
  905. lcd_update_enable(true);
  906. lcd_implementation_clear();
  907. }
  908. // Store the currently running firmware into an eeprom,
  909. // so the next time the firmware gets updated, it will know from which version it has been updated.
  910. update_current_firmware_version_to_eeprom();
  911. }
  912. // The loop() function is called in an endless loop by the Arduino framework from the default main() routine.
  913. // Before loop(), the setup() function is called by the main() routine.
  914. void loop()
  915. {
  916. if (usb_printing_counter > 0 && millis()-_usb_timer > 1000)
  917. {
  918. is_usb_printing = true;
  919. usb_printing_counter--;
  920. _usb_timer = millis();
  921. }
  922. if (usb_printing_counter == 0)
  923. {
  924. is_usb_printing = false;
  925. }
  926. get_command();
  927. #ifdef SDSUPPORT
  928. card.checkautostart(false);
  929. #endif
  930. if(buflen)
  931. {
  932. #ifdef SDSUPPORT
  933. if(card.saving)
  934. {
  935. // Saving a G-code file onto an SD-card is in progress.
  936. // Saving starts with M28, saving until M29 is seen.
  937. if(strstr_P(CMDBUFFER_CURRENT_STRING, PSTR("M29")) == NULL) {
  938. card.write_command(CMDBUFFER_CURRENT_STRING);
  939. if(card.logging)
  940. process_commands();
  941. else
  942. SERIAL_PROTOCOLLNRPGM(MSG_OK);
  943. } else {
  944. card.closefile();
  945. SERIAL_PROTOCOLLNRPGM(MSG_FILE_SAVED);
  946. }
  947. } else {
  948. process_commands();
  949. }
  950. #else
  951. process_commands();
  952. #endif //SDSUPPORT
  953. if (! cmdbuffer_front_already_processed)
  954. cmdqueue_pop_front();
  955. cmdbuffer_front_already_processed = false;
  956. }
  957. //check heater every n milliseconds
  958. manage_heater();
  959. manage_inactivity();
  960. checkHitEndstops();
  961. lcd_update();
  962. }
  963. void get_command()
  964. {
  965. // Test and reserve space for the new command string.
  966. if (! cmdqueue_could_enqueue_back(MAX_CMD_SIZE-1))
  967. return;
  968. while (MYSERIAL.available() > 0) {
  969. char serial_char = MYSERIAL.read();
  970. if (serial_char < 0)
  971. // Ignore extended ASCII characters. These characters have no meaning in the G-code apart from the file names
  972. // and Marlin does not support such file names anyway.
  973. // Serial characters with a highest bit set to 1 are generated when the USB cable is unplugged, leading
  974. // to a hang-up of the print process from an SD card.
  975. continue;
  976. if(serial_char == '\n' ||
  977. serial_char == '\r' ||
  978. (serial_char == ':' && comment_mode == false) ||
  979. serial_count >= (MAX_CMD_SIZE - 1) )
  980. {
  981. if(!serial_count) { //if empty line
  982. comment_mode = false; //for new command
  983. return;
  984. }
  985. cmdbuffer[bufindw+serial_count+1] = 0; //terminate string
  986. if(!comment_mode){
  987. comment_mode = false; //for new command
  988. if ((strchr_pointer = strchr(cmdbuffer+bufindw+1, 'N')) != NULL)
  989. {
  990. // Line number met. When sending a G-code over a serial line, each line may be stamped with its index,
  991. // and Marlin tests, whether the successive lines are stamped with an increasing line number ID.
  992. gcode_N = (strtol(strchr_pointer+1, NULL, 10));
  993. if(gcode_N != gcode_LastN+1 && (strstr_P(cmdbuffer+bufindw+1, PSTR("M110")) == NULL) ) {
  994. // M110 - set current line number.
  995. // Line numbers not sent in succession.
  996. SERIAL_ERROR_START;
  997. SERIAL_ERRORRPGM(MSG_ERR_LINE_NO);
  998. SERIAL_ERRORLN(gcode_LastN);
  999. //Serial.println(gcode_N);
  1000. FlushSerialRequestResend();
  1001. serial_count = 0;
  1002. return;
  1003. }
  1004. if((strchr_pointer = strchr(cmdbuffer+bufindw+1, '*')) != NULL)
  1005. {
  1006. byte checksum = 0;
  1007. char *p = cmdbuffer+bufindw+1;
  1008. while (p != strchr_pointer)
  1009. checksum = checksum^(*p++);
  1010. if (int(strtol(strchr_pointer+1, NULL, 10)) != int(checksum)) {
  1011. SERIAL_ERROR_START;
  1012. SERIAL_ERRORRPGM(MSG_ERR_CHECKSUM_MISMATCH);
  1013. SERIAL_ERRORLN(gcode_LastN);
  1014. FlushSerialRequestResend();
  1015. serial_count = 0;
  1016. return;
  1017. }
  1018. // If no errors, remove the checksum and continue parsing.
  1019. *strchr_pointer = 0;
  1020. }
  1021. else
  1022. {
  1023. SERIAL_ERROR_START;
  1024. SERIAL_ERRORRPGM(MSG_ERR_NO_CHECKSUM);
  1025. SERIAL_ERRORLN(gcode_LastN);
  1026. FlushSerialRequestResend();
  1027. serial_count = 0;
  1028. return;
  1029. }
  1030. gcode_LastN = gcode_N;
  1031. //if no errors, continue parsing
  1032. } // end of 'N' command
  1033. else // if we don't receive 'N' but still see '*'
  1034. {
  1035. if((strchr(cmdbuffer+bufindw+1, '*') != NULL))
  1036. {
  1037. SERIAL_ERROR_START;
  1038. SERIAL_ERRORRPGM(MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM);
  1039. SERIAL_ERRORLN(gcode_LastN);
  1040. serial_count = 0;
  1041. return;
  1042. }
  1043. } // end of '*' command
  1044. if ((strchr_pointer = strchr(cmdbuffer+bufindw+1, 'G')) != NULL) {
  1045. if (! IS_SD_PRINTING) {
  1046. usb_printing_counter = 10;
  1047. is_usb_printing = true;
  1048. }
  1049. if (Stopped == true) {
  1050. int gcode = strtol(strchr_pointer+1, NULL, 10);
  1051. if (gcode >= 0 && gcode <= 3) {
  1052. SERIAL_ERRORLNRPGM(MSG_ERR_STOPPED);
  1053. LCD_MESSAGERPGM(MSG_STOPPED);
  1054. }
  1055. }
  1056. } // end of 'G' command
  1057. //If command was e-stop process now
  1058. if(strcmp(cmdbuffer+bufindw+1, "M112") == 0)
  1059. kill();
  1060. // Store the current line into buffer, move to the next line.
  1061. cmdbuffer[bufindw] = CMDBUFFER_CURRENT_TYPE_USB;
  1062. #ifdef CMDBUFFER_DEBUG
  1063. SERIAL_ECHO_START;
  1064. SERIAL_ECHOPGM("Storing a command line to buffer: ");
  1065. SERIAL_ECHO(cmdbuffer+bufindw+1);
  1066. SERIAL_ECHOLNPGM("");
  1067. #endif /* CMDBUFFER_DEBUG */
  1068. bufindw += strlen(cmdbuffer+bufindw+1) + 2;
  1069. if (bufindw == sizeof(cmdbuffer))
  1070. bufindw = 0;
  1071. ++ buflen;
  1072. #ifdef CMDBUFFER_DEBUG
  1073. SERIAL_ECHOPGM("Number of commands in the buffer: ");
  1074. SERIAL_ECHO(buflen);
  1075. SERIAL_ECHOLNPGM("");
  1076. #endif /* CMDBUFFER_DEBUG */
  1077. } // end of 'not comment mode'
  1078. serial_count = 0; //clear buffer
  1079. // Don't call cmdqueue_could_enqueue_back if there are no characters waiting
  1080. // in the queue, as this function will reserve the memory.
  1081. if (MYSERIAL.available() == 0 || ! cmdqueue_could_enqueue_back(MAX_CMD_SIZE-1))
  1082. return;
  1083. } // end of "end of line" processing
  1084. else {
  1085. // Not an "end of line" symbol. Store the new character into a buffer.
  1086. if(serial_char == ';') comment_mode = true;
  1087. if(!comment_mode) cmdbuffer[bufindw+1+serial_count++] = serial_char;
  1088. }
  1089. } // end of serial line processing loop
  1090. #ifdef SDSUPPORT
  1091. if(!card.sdprinting || serial_count!=0){
  1092. // If there is a half filled buffer from serial line, wait until return before
  1093. // continuing with the serial line.
  1094. return;
  1095. }
  1096. //'#' stops reading from SD to the buffer prematurely, so procedural macro calls are possible
  1097. // if it occurs, stop_buffering is triggered and the buffer is ran dry.
  1098. // this character _can_ occur in serial com, due to checksums. however, no checksums are used in SD printing
  1099. static bool stop_buffering=false;
  1100. if(buflen==0) stop_buffering=false;
  1101. // Reads whole lines from the SD card. Never leaves a half-filled line in the cmdbuffer.
  1102. while( !card.eof() && !stop_buffering) {
  1103. int16_t n=card.get();
  1104. char serial_char = (char)n;
  1105. if(serial_char == '\n' ||
  1106. serial_char == '\r' ||
  1107. (serial_char == '#' && comment_mode == false) ||
  1108. (serial_char == ':' && comment_mode == false) ||
  1109. serial_count >= (MAX_CMD_SIZE - 1)||n==-1)
  1110. {
  1111. if(card.eof()){
  1112. SERIAL_PROTOCOLLNRPGM(MSG_FILE_PRINTED);
  1113. stoptime=millis();
  1114. char time[30];
  1115. unsigned long t=(stoptime-starttime)/1000;
  1116. int hours, minutes;
  1117. minutes=(t/60)%60;
  1118. hours=t/60/60;
  1119. save_statistics(total_filament_used, t);
  1120. sprintf_P(time, PSTR("%i hours %i minutes"),hours, minutes);
  1121. SERIAL_ECHO_START;
  1122. SERIAL_ECHOLN(time);
  1123. lcd_setstatus(time);
  1124. card.printingHasFinished();
  1125. card.checkautostart(true);
  1126. if (farm_mode)
  1127. {
  1128. prusa_statistics(6);
  1129. lcd_commands_type = 4;
  1130. }
  1131. }
  1132. if(serial_char=='#')
  1133. stop_buffering=true;
  1134. if(!serial_count)
  1135. {
  1136. comment_mode = false; //for new command
  1137. return; //if empty line
  1138. }
  1139. cmdbuffer[bufindw+serial_count+1] = 0; //terminate string
  1140. cmdbuffer[bufindw] = CMDBUFFER_CURRENT_TYPE_SDCARD;
  1141. ++ buflen;
  1142. bufindw += strlen(cmdbuffer+bufindw+1) + 2;
  1143. if (bufindw == sizeof(cmdbuffer))
  1144. bufindw = 0;
  1145. comment_mode = false; //for new command
  1146. serial_count = 0; //clear buffer
  1147. // The following line will reserve buffer space if available.
  1148. if (! cmdqueue_could_enqueue_back(MAX_CMD_SIZE-1))
  1149. return;
  1150. }
  1151. else
  1152. {
  1153. if(serial_char == ';') comment_mode = true;
  1154. if(!comment_mode) cmdbuffer[bufindw+1+serial_count++] = serial_char;
  1155. }
  1156. }
  1157. #endif //SDSUPPORT
  1158. }
  1159. // Return True if a character was found
  1160. static inline bool code_seen(char code) { return (strchr_pointer = strchr(CMDBUFFER_CURRENT_STRING, code)) != NULL; }
  1161. static inline bool code_seen(const char *code) { return (strchr_pointer = strstr(CMDBUFFER_CURRENT_STRING, code)) != NULL; }
  1162. static inline float code_value() { return strtod(strchr_pointer+1, NULL); }
  1163. static inline long code_value_long() { return strtol(strchr_pointer+1, NULL, 10); }
  1164. static inline int16_t code_value_short() { return int16_t(strtol(strchr_pointer+1, NULL, 10)); };
  1165. static inline uint8_t code_value_uint8() { return uint8_t(strtol(strchr_pointer+1, NULL, 10)); };
  1166. #define DEFINE_PGM_READ_ANY(type, reader) \
  1167. static inline type pgm_read_any(const type *p) \
  1168. { return pgm_read_##reader##_near(p); }
  1169. DEFINE_PGM_READ_ANY(float, float);
  1170. DEFINE_PGM_READ_ANY(signed char, byte);
  1171. #define XYZ_CONSTS_FROM_CONFIG(type, array, CONFIG) \
  1172. static const PROGMEM type array##_P[3] = \
  1173. { X_##CONFIG, Y_##CONFIG, Z_##CONFIG }; \
  1174. static inline type array(int axis) \
  1175. { return pgm_read_any(&array##_P[axis]); } \
  1176. type array##_ext(int axis) \
  1177. { return pgm_read_any(&array##_P[axis]); }
  1178. XYZ_CONSTS_FROM_CONFIG(float, base_min_pos, MIN_POS);
  1179. XYZ_CONSTS_FROM_CONFIG(float, base_max_pos, MAX_POS);
  1180. XYZ_CONSTS_FROM_CONFIG(float, base_home_pos, HOME_POS);
  1181. XYZ_CONSTS_FROM_CONFIG(float, max_length, MAX_LENGTH);
  1182. XYZ_CONSTS_FROM_CONFIG(float, home_retract_mm, HOME_RETRACT_MM);
  1183. XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR);
  1184. static void axis_is_at_home(int axis) {
  1185. current_position[axis] = base_home_pos(axis) + add_homing[axis];
  1186. min_pos[axis] = base_min_pos(axis) + add_homing[axis];
  1187. max_pos[axis] = base_max_pos(axis) + add_homing[axis];
  1188. }
  1189. inline void set_current_to_destination() { memcpy(current_position, destination, sizeof(current_position)); }
  1190. inline void set_destination_to_current() { memcpy(destination, current_position, sizeof(destination)); }
  1191. static void setup_for_endstop_move() {
  1192. saved_feedrate = feedrate;
  1193. saved_feedmultiply = feedmultiply;
  1194. feedmultiply = 100;
  1195. previous_millis_cmd = millis();
  1196. enable_endstops(true);
  1197. }
  1198. static void clean_up_after_endstop_move() {
  1199. #ifdef ENDSTOPS_ONLY_FOR_HOMING
  1200. enable_endstops(false);
  1201. #endif
  1202. feedrate = saved_feedrate;
  1203. feedmultiply = saved_feedmultiply;
  1204. previous_millis_cmd = millis();
  1205. }
  1206. #ifdef ENABLE_AUTO_BED_LEVELING
  1207. #ifdef AUTO_BED_LEVELING_GRID
  1208. static void set_bed_level_equation_lsq(double *plane_equation_coefficients)
  1209. {
  1210. vector_3 planeNormal = vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1);
  1211. planeNormal.debug("planeNormal");
  1212. plan_bed_level_matrix = matrix_3x3::create_look_at(planeNormal);
  1213. //bedLevel.debug("bedLevel");
  1214. //plan_bed_level_matrix.debug("bed level before");
  1215. //vector_3 uncorrected_position = plan_get_position_mm();
  1216. //uncorrected_position.debug("position before");
  1217. vector_3 corrected_position = plan_get_position();
  1218. // corrected_position.debug("position after");
  1219. current_position[X_AXIS] = corrected_position.x;
  1220. current_position[Y_AXIS] = corrected_position.y;
  1221. current_position[Z_AXIS] = corrected_position.z;
  1222. // put the bed at 0 so we don't go below it.
  1223. current_position[Z_AXIS] = zprobe_zoffset; // in the lsq we reach here after raising the extruder due to the loop structure
  1224. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1225. }
  1226. #else // not AUTO_BED_LEVELING_GRID
  1227. static void set_bed_level_equation_3pts(float z_at_pt_1, float z_at_pt_2, float z_at_pt_3) {
  1228. plan_bed_level_matrix.set_to_identity();
  1229. vector_3 pt1 = vector_3(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, z_at_pt_1);
  1230. vector_3 pt2 = vector_3(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, z_at_pt_2);
  1231. vector_3 pt3 = vector_3(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, z_at_pt_3);
  1232. vector_3 from_2_to_1 = (pt1 - pt2).get_normal();
  1233. vector_3 from_2_to_3 = (pt3 - pt2).get_normal();
  1234. vector_3 planeNormal = vector_3::cross(from_2_to_1, from_2_to_3).get_normal();
  1235. planeNormal = vector_3(planeNormal.x, planeNormal.y, abs(planeNormal.z));
  1236. plan_bed_level_matrix = matrix_3x3::create_look_at(planeNormal);
  1237. vector_3 corrected_position = plan_get_position();
  1238. current_position[X_AXIS] = corrected_position.x;
  1239. current_position[Y_AXIS] = corrected_position.y;
  1240. current_position[Z_AXIS] = corrected_position.z;
  1241. // put the bed at 0 so we don't go below it.
  1242. current_position[Z_AXIS] = zprobe_zoffset;
  1243. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1244. }
  1245. #endif // AUTO_BED_LEVELING_GRID
  1246. static void run_z_probe() {
  1247. plan_bed_level_matrix.set_to_identity();
  1248. feedrate = homing_feedrate[Z_AXIS];
  1249. // move down until you find the bed
  1250. float zPosition = -10;
  1251. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate/60, active_extruder);
  1252. st_synchronize();
  1253. // we have to let the planner know where we are right now as it is not where we said to go.
  1254. zPosition = st_get_position_mm(Z_AXIS);
  1255. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS]);
  1256. // move up the retract distance
  1257. zPosition += home_retract_mm(Z_AXIS);
  1258. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate/60, active_extruder);
  1259. st_synchronize();
  1260. // move back down slowly to find bed
  1261. feedrate = homing_feedrate[Z_AXIS]/4;
  1262. zPosition -= home_retract_mm(Z_AXIS) * 2;
  1263. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate/60, active_extruder);
  1264. st_synchronize();
  1265. current_position[Z_AXIS] = st_get_position_mm(Z_AXIS);
  1266. // make sure the planner knows where we are as it may be a bit different than we last said to move to
  1267. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1268. }
  1269. static void do_blocking_move_to(float x, float y, float z) {
  1270. float oldFeedRate = feedrate;
  1271. feedrate = homing_feedrate[Z_AXIS];
  1272. current_position[Z_AXIS] = z;
  1273. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate/60, active_extruder);
  1274. st_synchronize();
  1275. feedrate = XY_TRAVEL_SPEED;
  1276. current_position[X_AXIS] = x;
  1277. current_position[Y_AXIS] = y;
  1278. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate/60, active_extruder);
  1279. st_synchronize();
  1280. feedrate = oldFeedRate;
  1281. }
  1282. static void do_blocking_move_relative(float offset_x, float offset_y, float offset_z) {
  1283. do_blocking_move_to(current_position[X_AXIS] + offset_x, current_position[Y_AXIS] + offset_y, current_position[Z_AXIS] + offset_z);
  1284. }
  1285. /// Probe bed height at position (x,y), returns the measured z value
  1286. static float probe_pt(float x, float y, float z_before) {
  1287. // move to right place
  1288. do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z_before);
  1289. do_blocking_move_to(x - X_PROBE_OFFSET_FROM_EXTRUDER, y - Y_PROBE_OFFSET_FROM_EXTRUDER, current_position[Z_AXIS]);
  1290. run_z_probe();
  1291. float measured_z = current_position[Z_AXIS];
  1292. SERIAL_PROTOCOLRPGM(MSG_BED);
  1293. SERIAL_PROTOCOLPGM(" x: ");
  1294. SERIAL_PROTOCOL(x);
  1295. SERIAL_PROTOCOLPGM(" y: ");
  1296. SERIAL_PROTOCOL(y);
  1297. SERIAL_PROTOCOLPGM(" z: ");
  1298. SERIAL_PROTOCOL(measured_z);
  1299. SERIAL_PROTOCOLPGM("\n");
  1300. return measured_z;
  1301. }
  1302. #endif // #ifdef ENABLE_AUTO_BED_LEVELING
  1303. void homeaxis(int axis) {
  1304. #define HOMEAXIS_DO(LETTER) \
  1305. ((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1))
  1306. if (axis==X_AXIS ? HOMEAXIS_DO(X) :
  1307. axis==Y_AXIS ? HOMEAXIS_DO(Y) :
  1308. axis==Z_AXIS ? HOMEAXIS_DO(Z) :
  1309. 0) {
  1310. int axis_home_dir = home_dir(axis);
  1311. current_position[axis] = 0;
  1312. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1313. destination[axis] = 1.5 * max_length(axis) * axis_home_dir;
  1314. feedrate = homing_feedrate[axis];
  1315. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1316. st_synchronize();
  1317. current_position[axis] = 0;
  1318. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1319. destination[axis] = -home_retract_mm(axis) * axis_home_dir;
  1320. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1321. st_synchronize();
  1322. destination[axis] = 2*home_retract_mm(axis) * axis_home_dir;
  1323. feedrate = homing_feedrate[axis]/2 ;
  1324. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1325. st_synchronize();
  1326. axis_is_at_home(axis);
  1327. destination[axis] = current_position[axis];
  1328. feedrate = 0.0;
  1329. endstops_hit_on_purpose();
  1330. axis_known_position[axis] = true;
  1331. }
  1332. }
  1333. void home_xy()
  1334. {
  1335. set_destination_to_current();
  1336. homeaxis(X_AXIS);
  1337. homeaxis(Y_AXIS);
  1338. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1339. endstops_hit_on_purpose();
  1340. }
  1341. void refresh_cmd_timeout(void)
  1342. {
  1343. previous_millis_cmd = millis();
  1344. }
  1345. #ifdef FWRETRACT
  1346. void retract(bool retracting, bool swapretract = false) {
  1347. if(retracting && !retracted[active_extruder]) {
  1348. destination[X_AXIS]=current_position[X_AXIS];
  1349. destination[Y_AXIS]=current_position[Y_AXIS];
  1350. destination[Z_AXIS]=current_position[Z_AXIS];
  1351. destination[E_AXIS]=current_position[E_AXIS];
  1352. if (swapretract) {
  1353. current_position[E_AXIS]+=retract_length_swap/volumetric_multiplier[active_extruder];
  1354. } else {
  1355. current_position[E_AXIS]+=retract_length/volumetric_multiplier[active_extruder];
  1356. }
  1357. plan_set_e_position(current_position[E_AXIS]);
  1358. float oldFeedrate = feedrate;
  1359. feedrate=retract_feedrate*60;
  1360. retracted[active_extruder]=true;
  1361. prepare_move();
  1362. current_position[Z_AXIS]-=retract_zlift;
  1363. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1364. prepare_move();
  1365. feedrate = oldFeedrate;
  1366. } else if(!retracting && retracted[active_extruder]) {
  1367. destination[X_AXIS]=current_position[X_AXIS];
  1368. destination[Y_AXIS]=current_position[Y_AXIS];
  1369. destination[Z_AXIS]=current_position[Z_AXIS];
  1370. destination[E_AXIS]=current_position[E_AXIS];
  1371. current_position[Z_AXIS]+=retract_zlift;
  1372. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1373. //prepare_move();
  1374. if (swapretract) {
  1375. current_position[E_AXIS]-=(retract_length_swap+retract_recover_length_swap)/volumetric_multiplier[active_extruder];
  1376. } else {
  1377. current_position[E_AXIS]-=(retract_length+retract_recover_length)/volumetric_multiplier[active_extruder];
  1378. }
  1379. plan_set_e_position(current_position[E_AXIS]);
  1380. float oldFeedrate = feedrate;
  1381. feedrate=retract_recover_feedrate*60;
  1382. retracted[active_extruder]=false;
  1383. prepare_move();
  1384. feedrate = oldFeedrate;
  1385. }
  1386. } //retract
  1387. #endif //FWRETRACT
  1388. void process_commands()
  1389. {
  1390. #ifdef FILAMENT_RUNOUT_SUPPORT
  1391. SET_INPUT(FR_SENS);
  1392. #endif
  1393. #ifdef CMDBUFFER_DEBUG
  1394. SERIAL_ECHOPGM("Processing a GCODE command: ");
  1395. SERIAL_ECHO(cmdbuffer+bufindr+1);
  1396. SERIAL_ECHOLNPGM("");
  1397. SERIAL_ECHOPGM("In cmdqueue: ");
  1398. SERIAL_ECHO(buflen);
  1399. SERIAL_ECHOLNPGM("");
  1400. #endif /* CMDBUFFER_DEBUG */
  1401. unsigned long codenum; //throw away variable
  1402. char *starpos = NULL;
  1403. #ifdef ENABLE_AUTO_BED_LEVELING
  1404. float x_tmp, y_tmp, z_tmp, real_z;
  1405. #endif
  1406. // PRUSA GCODES
  1407. if(code_seen("PRUSA")){
  1408. if(code_seen("Fir")){
  1409. SERIAL_PROTOCOLLN(FW_version);
  1410. } else if(code_seen("Rev")){
  1411. SERIAL_PROTOCOLLN(FILAMENT_SIZE "-" ELECTRONICS "-" NOZZLE_TYPE );
  1412. } else if(code_seen("Lang")) {
  1413. lcd_force_language_selection();
  1414. } else if(code_seen("Lz")) {
  1415. EEPROM_save_B(EEPROM_BABYSTEP_Z,0);
  1416. }
  1417. //else if (code_seen('Cal')) {
  1418. // lcd_calibration();
  1419. // }
  1420. }
  1421. else
  1422. if(code_seen('G'))
  1423. {
  1424. switch((int)code_value())
  1425. {
  1426. case 0: // G0 -> G1
  1427. case 1: // G1
  1428. if(Stopped == false) {
  1429. #ifdef FILAMENT_RUNOUT_SUPPORT
  1430. if(READ(FR_SENS)){
  1431. feedmultiplyBckp=feedmultiply;
  1432. float target[4];
  1433. float lastpos[4];
  1434. target[X_AXIS]=current_position[X_AXIS];
  1435. target[Y_AXIS]=current_position[Y_AXIS];
  1436. target[Z_AXIS]=current_position[Z_AXIS];
  1437. target[E_AXIS]=current_position[E_AXIS];
  1438. lastpos[X_AXIS]=current_position[X_AXIS];
  1439. lastpos[Y_AXIS]=current_position[Y_AXIS];
  1440. lastpos[Z_AXIS]=current_position[Z_AXIS];
  1441. lastpos[E_AXIS]=current_position[E_AXIS];
  1442. //retract by E
  1443. target[E_AXIS]+= FILAMENTCHANGE_FIRSTRETRACT ;
  1444. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 400, active_extruder);
  1445. target[Z_AXIS]+= FILAMENTCHANGE_ZADD ;
  1446. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 300, active_extruder);
  1447. target[X_AXIS]= FILAMENTCHANGE_XPOS ;
  1448. target[Y_AXIS]= FILAMENTCHANGE_YPOS ;
  1449. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 70, active_extruder);
  1450. target[E_AXIS]+= FILAMENTCHANGE_FINALRETRACT ;
  1451. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 20, active_extruder);
  1452. //finish moves
  1453. st_synchronize();
  1454. //disable extruder steppers so filament can be removed
  1455. disable_e0();
  1456. disable_e1();
  1457. disable_e2();
  1458. delay(100);
  1459. //LCD_ALERTMESSAGEPGM(MSG_FILAMENTCHANGE);
  1460. uint8_t cnt=0;
  1461. int counterBeep = 0;
  1462. lcd_wait_interact();
  1463. while(!lcd_clicked()){
  1464. cnt++;
  1465. manage_heater();
  1466. manage_inactivity(true);
  1467. //lcd_update();
  1468. if(cnt==0)
  1469. {
  1470. #if BEEPER > 0
  1471. if (counterBeep== 500){
  1472. counterBeep = 0;
  1473. }
  1474. SET_OUTPUT(BEEPER);
  1475. if (counterBeep== 0){
  1476. WRITE(BEEPER,HIGH);
  1477. }
  1478. if (counterBeep== 20){
  1479. WRITE(BEEPER,LOW);
  1480. }
  1481. counterBeep++;
  1482. #else
  1483. #if !defined(LCD_FEEDBACK_FREQUENCY_HZ) || !defined(LCD_FEEDBACK_FREQUENCY_DURATION_MS)
  1484. lcd_buzz(1000/6,100);
  1485. #else
  1486. lcd_buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS,LCD_FEEDBACK_FREQUENCY_HZ);
  1487. #endif
  1488. #endif
  1489. }
  1490. }
  1491. WRITE(BEEPER,LOW);
  1492. target[E_AXIS]+= FILAMENTCHANGE_FIRSTFEED ;
  1493. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 20, active_extruder);
  1494. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  1495. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  1496. lcd_change_fil_state = 0;
  1497. lcd_loading_filament();
  1498. while ((lcd_change_fil_state == 0)||(lcd_change_fil_state != 1)){
  1499. lcd_change_fil_state = 0;
  1500. lcd_alright();
  1501. switch(lcd_change_fil_state){
  1502. case 2:
  1503. target[E_AXIS]+= FILAMENTCHANGE_FIRSTFEED ;
  1504. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 20, active_extruder);
  1505. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  1506. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  1507. lcd_loading_filament();
  1508. break;
  1509. case 3:
  1510. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  1511. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  1512. lcd_loading_color();
  1513. break;
  1514. default:
  1515. lcd_change_success();
  1516. break;
  1517. }
  1518. }
  1519. target[E_AXIS]+= 5;
  1520. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  1521. target[E_AXIS]+= FILAMENTCHANGE_FIRSTRETRACT;
  1522. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 400, active_extruder);
  1523. //current_position[E_AXIS]=target[E_AXIS]; //the long retract of L is compensated by manual filament feeding
  1524. //plan_set_e_position(current_position[E_AXIS]);
  1525. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 70, active_extruder); //should do nothing
  1526. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], target[Z_AXIS], target[E_AXIS], 70, active_extruder); //move xy back
  1527. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], target[E_AXIS], 200, active_extruder); //move z back
  1528. target[E_AXIS]= target[E_AXIS] - FILAMENTCHANGE_FIRSTRETRACT;
  1529. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], target[E_AXIS], 5, active_extruder); //final untretract
  1530. plan_set_e_position(lastpos[E_AXIS]);
  1531. feedmultiply=feedmultiplyBckp;
  1532. char cmd[9];
  1533. sprintf_P(cmd, PSTR("M220 S%i"), feedmultiplyBckp);
  1534. enquecommand(cmd);
  1535. }
  1536. #endif
  1537. get_coordinates(); // For X Y Z E F
  1538. total_filament_used = total_filament_used + ((destination[E_AXIS] - current_position[E_AXIS])*100);
  1539. #ifdef FWRETRACT
  1540. if(autoretract_enabled)
  1541. if( !(code_seen('X') || code_seen('Y') || code_seen('Z')) && code_seen('E')) {
  1542. float echange=destination[E_AXIS]-current_position[E_AXIS];
  1543. if((echange<-MIN_RETRACT && !retracted) || (echange>MIN_RETRACT && retracted)) { //move appears to be an attempt to retract or recover
  1544. current_position[E_AXIS] = destination[E_AXIS]; //hide the slicer-generated retract/recover from calculations
  1545. plan_set_e_position(current_position[E_AXIS]); //AND from the planner
  1546. retract(!retracted);
  1547. return;
  1548. }
  1549. }
  1550. #endif //FWRETRACT
  1551. prepare_move();
  1552. //ClearToSend();
  1553. }
  1554. break;
  1555. case 2: // G2 - CW ARC
  1556. if(Stopped == false) {
  1557. get_arc_coordinates();
  1558. prepare_arc_move(true);
  1559. }
  1560. break;
  1561. case 3: // G3 - CCW ARC
  1562. if(Stopped == false) {
  1563. get_arc_coordinates();
  1564. prepare_arc_move(false);
  1565. }
  1566. break;
  1567. case 4: // G4 dwell
  1568. LCD_MESSAGERPGM(MSG_DWELL);
  1569. codenum = 0;
  1570. if(code_seen('P')) codenum = code_value(); // milliseconds to wait
  1571. if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait
  1572. st_synchronize();
  1573. codenum += millis(); // keep track of when we started waiting
  1574. previous_millis_cmd = millis();
  1575. while(millis() < codenum) {
  1576. manage_heater();
  1577. manage_inactivity();
  1578. lcd_update();
  1579. }
  1580. break;
  1581. #ifdef FWRETRACT
  1582. case 10: // G10 retract
  1583. #if EXTRUDERS > 1
  1584. retracted_swap[active_extruder]=(code_seen('S') && code_value_long() == 1); // checks for swap retract argument
  1585. retract(true,retracted_swap[active_extruder]);
  1586. #else
  1587. retract(true);
  1588. #endif
  1589. break;
  1590. case 11: // G11 retract_recover
  1591. #if EXTRUDERS > 1
  1592. retract(false,retracted_swap[active_extruder]);
  1593. #else
  1594. retract(false);
  1595. #endif
  1596. break;
  1597. #endif //FWRETRACT
  1598. case 28: //G28 Home all Axis one at a time
  1599. #ifdef ENABLE_AUTO_BED_LEVELING
  1600. plan_bed_level_matrix.set_to_identity(); //Reset the plane ("erase" all leveling data)
  1601. #endif //ENABLE_AUTO_BED_LEVELING
  1602. // For mesh bed leveling deactivate the matrix temporarily
  1603. #ifdef MESH_BED_LEVELING
  1604. mbl.active = 0;
  1605. #endif
  1606. // Reset world2machine_rotation_and_skew and world2machine_shift, therefore
  1607. // the planner will not perform any adjustments in the XY plane.
  1608. // Wait for the motors to stop and update the current position with the absolute values.
  1609. world2machine_revert_to_uncorrected();
  1610. // Reset baby stepping to zero, if the babystepping has already been loaded before. The babystepsTodo value will be
  1611. // consumed during the first movements following this statement.
  1612. #ifdef BABYSTEP_LOADZ_BY_PLANNER
  1613. shift_z(float(babystepLoadZ) / float(axis_steps_per_unit[Z_AXIS]));
  1614. #else
  1615. babystepsTodoZsubtract(babystepLoadZ);
  1616. #endif /* BABYSTEP_LOADZ_BY_PLANNER */
  1617. babystepLoadZ = 0;
  1618. saved_feedrate = feedrate;
  1619. saved_feedmultiply = feedmultiply;
  1620. feedmultiply = 100;
  1621. previous_millis_cmd = millis();
  1622. enable_endstops(true);
  1623. for(int8_t i=0; i < NUM_AXIS; i++)
  1624. destination[i] = current_position[i];
  1625. feedrate = 0.0;
  1626. home_all_axis = !((code_seen(axis_codes[X_AXIS])) || (code_seen(axis_codes[Y_AXIS])) || (code_seen(axis_codes[Z_AXIS])));
  1627. #if Z_HOME_DIR > 0 // If homing away from BED do Z first
  1628. if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
  1629. homeaxis(Z_AXIS);
  1630. }
  1631. #endif
  1632. #ifdef QUICK_HOME
  1633. // In the quick mode, if both x and y are to be homed, a diagonal move will be performed initially.
  1634. if((home_all_axis)||( code_seen(axis_codes[X_AXIS]) && code_seen(axis_codes[Y_AXIS])) ) //first diagonal move
  1635. {
  1636. current_position[X_AXIS] = 0;current_position[Y_AXIS] = 0;
  1637. int x_axis_home_dir = home_dir(X_AXIS);
  1638. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1639. 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);
  1640. feedrate = homing_feedrate[X_AXIS];
  1641. if(homing_feedrate[Y_AXIS]<feedrate)
  1642. feedrate = homing_feedrate[Y_AXIS];
  1643. if (max_length(X_AXIS) > max_length(Y_AXIS)) {
  1644. feedrate *= sqrt(pow(max_length(Y_AXIS) / max_length(X_AXIS), 2) + 1);
  1645. } else {
  1646. feedrate *= sqrt(pow(max_length(X_AXIS) / max_length(Y_AXIS), 2) + 1);
  1647. }
  1648. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1649. st_synchronize();
  1650. axis_is_at_home(X_AXIS);
  1651. axis_is_at_home(Y_AXIS);
  1652. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1653. destination[X_AXIS] = current_position[X_AXIS];
  1654. destination[Y_AXIS] = current_position[Y_AXIS];
  1655. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  1656. feedrate = 0.0;
  1657. st_synchronize();
  1658. endstops_hit_on_purpose();
  1659. current_position[X_AXIS] = destination[X_AXIS];
  1660. current_position[Y_AXIS] = destination[Y_AXIS];
  1661. current_position[Z_AXIS] = destination[Z_AXIS];
  1662. }
  1663. #endif /* QUICK_HOME */
  1664. if((home_all_axis) || (code_seen(axis_codes[X_AXIS])))
  1665. homeaxis(X_AXIS);
  1666. if((home_all_axis) || (code_seen(axis_codes[Y_AXIS])))
  1667. homeaxis(Y_AXIS);
  1668. if(code_seen(axis_codes[X_AXIS]) && code_value_long() != 0)
  1669. current_position[X_AXIS]=code_value()+add_homing[X_AXIS];
  1670. if(code_seen(axis_codes[Y_AXIS]) && code_value_long() != 0)
  1671. current_position[Y_AXIS]=code_value()+add_homing[Y_AXIS];
  1672. #if Z_HOME_DIR < 0 // If homing towards BED do Z last
  1673. #ifndef Z_SAFE_HOMING
  1674. if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
  1675. #if defined (Z_RAISE_BEFORE_HOMING) && (Z_RAISE_BEFORE_HOMING > 0)
  1676. destination[Z_AXIS] = Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS) * (-1); // Set destination away from bed
  1677. feedrate = max_feedrate[Z_AXIS];
  1678. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
  1679. st_synchronize();
  1680. #endif // defined (Z_RAISE_BEFORE_HOMING) && (Z_RAISE_BEFORE_HOMING > 0)
  1681. #ifdef MESH_BED_LEVELING // If Mesh bed leveling, moxve X&Y to safe position for home
  1682. if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] ))
  1683. {
  1684. homeaxis(X_AXIS);
  1685. homeaxis(Y_AXIS);
  1686. }
  1687. // 1st mesh bed leveling measurement point, corrected.
  1688. world2machine_initialize();
  1689. world2machine(pgm_read_float(bed_ref_points), pgm_read_float(bed_ref_points+1), destination[X_AXIS], destination[Y_AXIS]);
  1690. world2machine_reset();
  1691. if (destination[Y_AXIS] < Y_MIN_POS)
  1692. destination[Y_AXIS] = Y_MIN_POS;
  1693. destination[Z_AXIS] = MESH_HOME_Z_SEARCH; // Set destination away from bed
  1694. feedrate = homing_feedrate[Z_AXIS]/10;
  1695. current_position[Z_AXIS] = 0;
  1696. enable_endstops(false);
  1697. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1698. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
  1699. st_synchronize();
  1700. current_position[X_AXIS] = destination[X_AXIS];
  1701. current_position[Y_AXIS] = destination[Y_AXIS];
  1702. enable_endstops(true);
  1703. endstops_hit_on_purpose();
  1704. homeaxis(Z_AXIS);
  1705. #else // MESH_BED_LEVELING
  1706. homeaxis(Z_AXIS);
  1707. #endif // MESH_BED_LEVELING
  1708. }
  1709. #else // defined(Z_SAFE_HOMING): Z Safe mode activated.
  1710. if(home_all_axis) {
  1711. destination[X_AXIS] = round(Z_SAFE_HOMING_X_POINT - X_PROBE_OFFSET_FROM_EXTRUDER);
  1712. destination[Y_AXIS] = round(Z_SAFE_HOMING_Y_POINT - Y_PROBE_OFFSET_FROM_EXTRUDER);
  1713. destination[Z_AXIS] = Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS) * (-1); // Set destination away from bed
  1714. feedrate = XY_TRAVEL_SPEED/60;
  1715. current_position[Z_AXIS] = 0;
  1716. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1717. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
  1718. st_synchronize();
  1719. current_position[X_AXIS] = destination[X_AXIS];
  1720. current_position[Y_AXIS] = destination[Y_AXIS];
  1721. homeaxis(Z_AXIS);
  1722. }
  1723. // Let's see if X and Y are homed and probe is inside bed area.
  1724. if(code_seen(axis_codes[Z_AXIS])) {
  1725. if ( (axis_known_position[X_AXIS]) && (axis_known_position[Y_AXIS]) \
  1726. && (current_position[X_AXIS]+X_PROBE_OFFSET_FROM_EXTRUDER >= X_MIN_POS) \
  1727. && (current_position[X_AXIS]+X_PROBE_OFFSET_FROM_EXTRUDER <= X_MAX_POS) \
  1728. && (current_position[Y_AXIS]+Y_PROBE_OFFSET_FROM_EXTRUDER >= Y_MIN_POS) \
  1729. && (current_position[Y_AXIS]+Y_PROBE_OFFSET_FROM_EXTRUDER <= Y_MAX_POS)) {
  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. destination[Z_AXIS] = Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS) * (-1); // Set destination away from bed
  1733. feedrate = max_feedrate[Z_AXIS];
  1734. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
  1735. st_synchronize();
  1736. homeaxis(Z_AXIS);
  1737. } else if (!((axis_known_position[X_AXIS]) && (axis_known_position[Y_AXIS]))) {
  1738. LCD_MESSAGERPGM(MSG_POSITION_UNKNOWN);
  1739. SERIAL_ECHO_START;
  1740. SERIAL_ECHOLNRPGM(MSG_POSITION_UNKNOWN);
  1741. } else {
  1742. LCD_MESSAGERPGM(MSG_ZPROBE_OUT);
  1743. SERIAL_ECHO_START;
  1744. SERIAL_ECHOLNRPGM(MSG_ZPROBE_OUT);
  1745. }
  1746. }
  1747. #endif // Z_SAFE_HOMING
  1748. #endif // Z_HOME_DIR < 0
  1749. if(code_seen(axis_codes[Z_AXIS])) {
  1750. if(code_value_long() != 0) {
  1751. current_position[Z_AXIS]=code_value()+add_homing[Z_AXIS];
  1752. }
  1753. }
  1754. #ifdef ENABLE_AUTO_BED_LEVELING
  1755. if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
  1756. current_position[Z_AXIS] += zprobe_zoffset; //Add Z_Probe offset (the distance is negative)
  1757. }
  1758. #endif
  1759. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1760. #ifdef ENDSTOPS_ONLY_FOR_HOMING
  1761. enable_endstops(false);
  1762. #endif
  1763. feedrate = saved_feedrate;
  1764. feedmultiply = saved_feedmultiply;
  1765. previous_millis_cmd = millis();
  1766. endstops_hit_on_purpose();
  1767. #ifndef MESH_BED_LEVELING
  1768. // If MESH_BED_LEVELING is not active, then it is the original Prusa i3.
  1769. // Offer the user to load the baby step value, which has been adjusted at the previous print session.
  1770. if(card.sdprinting) {
  1771. EEPROM_read_B(EEPROM_BABYSTEP_Z,&babystepLoadZ);
  1772. if(babystepLoadZ != 0)
  1773. lcd_adjust_z();
  1774. }
  1775. #endif
  1776. // Load the machine correction matrix
  1777. world2machine_initialize();
  1778. // and correct the current_position to match the transformed coordinate system.
  1779. world2machine_update_current();
  1780. #ifdef MESH_BED_LEVELING
  1781. if (code_seen(axis_codes[X_AXIS]) || code_seen(axis_codes[Y_AXIS]) || code_seen('W') || code_seen(axis_codes[Z_AXIS]))
  1782. {
  1783. }
  1784. else
  1785. {
  1786. st_synchronize();
  1787. // Push the commands to the front of the message queue in the reverse order!
  1788. // There shall be always enough space reserved for these commands.
  1789. // enquecommand_front_P((PSTR("G80")));
  1790. goto case_G80;
  1791. }
  1792. #endif
  1793. if (farm_mode) { prusa_statistics(20); };
  1794. break;
  1795. #ifdef ENABLE_AUTO_BED_LEVELING
  1796. case 29: // G29 Detailed Z-Probe, probes the bed at 3 or more points.
  1797. {
  1798. #if Z_MIN_PIN == -1
  1799. #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."
  1800. #endif
  1801. // Prevent user from running a G29 without first homing in X and Y
  1802. if (! (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS]) )
  1803. {
  1804. LCD_MESSAGERPGM(MSG_POSITION_UNKNOWN);
  1805. SERIAL_ECHO_START;
  1806. SERIAL_ECHOLNRPGM(MSG_POSITION_UNKNOWN);
  1807. break; // abort G29, since we don't know where we are
  1808. }
  1809. st_synchronize();
  1810. // make sure the bed_level_rotation_matrix is identity or the planner will get it incorectly
  1811. //vector_3 corrected_position = plan_get_position_mm();
  1812. //corrected_position.debug("position before G29");
  1813. plan_bed_level_matrix.set_to_identity();
  1814. vector_3 uncorrected_position = plan_get_position();
  1815. //uncorrected_position.debug("position durring G29");
  1816. current_position[X_AXIS] = uncorrected_position.x;
  1817. current_position[Y_AXIS] = uncorrected_position.y;
  1818. current_position[Z_AXIS] = uncorrected_position.z;
  1819. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1820. setup_for_endstop_move();
  1821. feedrate = homing_feedrate[Z_AXIS];
  1822. #ifdef AUTO_BED_LEVELING_GRID
  1823. // probe at the points of a lattice grid
  1824. int xGridSpacing = (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION) / (AUTO_BED_LEVELING_GRID_POINTS-1);
  1825. int yGridSpacing = (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION) / (AUTO_BED_LEVELING_GRID_POINTS-1);
  1826. // solve the plane equation ax + by + d = z
  1827. // A is the matrix with rows [x y 1] for all the probed points
  1828. // B is the vector of the Z positions
  1829. // 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
  1830. // so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z
  1831. // "A" matrix of the linear system of equations
  1832. double eqnAMatrix[AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS*3];
  1833. // "B" vector of Z points
  1834. double eqnBVector[AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS];
  1835. int probePointCounter = 0;
  1836. bool zig = true;
  1837. for (int yProbe=FRONT_PROBE_BED_POSITION; yProbe <= BACK_PROBE_BED_POSITION; yProbe += yGridSpacing)
  1838. {
  1839. int xProbe, xInc;
  1840. if (zig)
  1841. {
  1842. xProbe = LEFT_PROBE_BED_POSITION;
  1843. //xEnd = RIGHT_PROBE_BED_POSITION;
  1844. xInc = xGridSpacing;
  1845. zig = false;
  1846. } else // zag
  1847. {
  1848. xProbe = RIGHT_PROBE_BED_POSITION;
  1849. //xEnd = LEFT_PROBE_BED_POSITION;
  1850. xInc = -xGridSpacing;
  1851. zig = true;
  1852. }
  1853. for (int xCount=0; xCount < AUTO_BED_LEVELING_GRID_POINTS; xCount++)
  1854. {
  1855. float z_before;
  1856. if (probePointCounter == 0)
  1857. {
  1858. // raise before probing
  1859. z_before = Z_RAISE_BEFORE_PROBING;
  1860. } else
  1861. {
  1862. // raise extruder
  1863. z_before = current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS;
  1864. }
  1865. float measured_z = probe_pt(xProbe, yProbe, z_before);
  1866. eqnBVector[probePointCounter] = measured_z;
  1867. eqnAMatrix[probePointCounter + 0*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = xProbe;
  1868. eqnAMatrix[probePointCounter + 1*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = yProbe;
  1869. eqnAMatrix[probePointCounter + 2*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = 1;
  1870. probePointCounter++;
  1871. xProbe += xInc;
  1872. }
  1873. }
  1874. clean_up_after_endstop_move();
  1875. // solve lsq problem
  1876. double *plane_equation_coefficients = qr_solve(AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS, 3, eqnAMatrix, eqnBVector);
  1877. SERIAL_PROTOCOLPGM("Eqn coefficients: a: ");
  1878. SERIAL_PROTOCOL(plane_equation_coefficients[0]);
  1879. SERIAL_PROTOCOLPGM(" b: ");
  1880. SERIAL_PROTOCOL(plane_equation_coefficients[1]);
  1881. SERIAL_PROTOCOLPGM(" d: ");
  1882. SERIAL_PROTOCOLLN(plane_equation_coefficients[2]);
  1883. set_bed_level_equation_lsq(plane_equation_coefficients);
  1884. free(plane_equation_coefficients);
  1885. #else // AUTO_BED_LEVELING_GRID not defined
  1886. // Probe at 3 arbitrary points
  1887. // probe 1
  1888. float z_at_pt_1 = probe_pt(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, Z_RAISE_BEFORE_PROBING);
  1889. // probe 2
  1890. 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);
  1891. // probe 3
  1892. 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);
  1893. clean_up_after_endstop_move();
  1894. set_bed_level_equation_3pts(z_at_pt_1, z_at_pt_2, z_at_pt_3);
  1895. #endif // AUTO_BED_LEVELING_GRID
  1896. st_synchronize();
  1897. // The following code correct the Z height difference from z-probe position and hotend tip position.
  1898. // The Z height on homing is measured by Z-Probe, but the probe is quite far from the hotend.
  1899. // When the bed is uneven, this height must be corrected.
  1900. 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)
  1901. x_tmp = current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER;
  1902. y_tmp = current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER;
  1903. z_tmp = current_position[Z_AXIS];
  1904. apply_rotation_xyz(plan_bed_level_matrix, x_tmp, y_tmp, z_tmp); //Apply the correction sending the probe offset
  1905. current_position[Z_AXIS] = z_tmp - real_z + current_position[Z_AXIS]; //The difference is added to current position and sent to planner.
  1906. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  1907. }
  1908. break;
  1909. #ifndef Z_PROBE_SLED
  1910. case 30: // G30 Single Z Probe
  1911. {
  1912. st_synchronize();
  1913. // TODO: make sure the bed_level_rotation_matrix is identity or the planner will get set incorectly
  1914. setup_for_endstop_move();
  1915. feedrate = homing_feedrate[Z_AXIS];
  1916. run_z_probe();
  1917. SERIAL_PROTOCOLPGM(MSG_BED);
  1918. SERIAL_PROTOCOLPGM(" X: ");
  1919. SERIAL_PROTOCOL(current_position[X_AXIS]);
  1920. SERIAL_PROTOCOLPGM(" Y: ");
  1921. SERIAL_PROTOCOL(current_position[Y_AXIS]);
  1922. SERIAL_PROTOCOLPGM(" Z: ");
  1923. SERIAL_PROTOCOL(current_position[Z_AXIS]);
  1924. SERIAL_PROTOCOLPGM("\n");
  1925. clean_up_after_endstop_move();
  1926. }
  1927. break;
  1928. #else
  1929. case 31: // dock the sled
  1930. dock_sled(true);
  1931. break;
  1932. case 32: // undock the sled
  1933. dock_sled(false);
  1934. break;
  1935. #endif // Z_PROBE_SLED
  1936. #endif // ENABLE_AUTO_BED_LEVELING
  1937. #ifdef MESH_BED_LEVELING
  1938. case 30: // G30 Single Z Probe
  1939. {
  1940. st_synchronize();
  1941. // TODO: make sure the bed_level_rotation_matrix is identity or the planner will get set incorectly
  1942. setup_for_endstop_move();
  1943. feedrate = homing_feedrate[Z_AXIS];
  1944. find_bed_induction_sensor_point_z(-10.f, 3);
  1945. SERIAL_PROTOCOLRPGM(MSG_BED);
  1946. SERIAL_PROTOCOLPGM(" X: ");
  1947. MYSERIAL.print(current_position[X_AXIS], 5);
  1948. SERIAL_PROTOCOLPGM(" Y: ");
  1949. MYSERIAL.print(current_position[Y_AXIS], 5);
  1950. SERIAL_PROTOCOLPGM(" Z: ");
  1951. MYSERIAL.print(current_position[Z_AXIS], 5);
  1952. SERIAL_PROTOCOLPGM("\n");
  1953. clean_up_after_endstop_move();
  1954. }
  1955. break;
  1956. /**
  1957. * G80: Mesh-based Z probe, probes a grid and produces a
  1958. * mesh to compensate for variable bed height
  1959. *
  1960. * The S0 report the points as below
  1961. *
  1962. * +----> X-axis
  1963. * |
  1964. * |
  1965. * v Y-axis
  1966. *
  1967. */
  1968. case 80:
  1969. case_G80:
  1970. {
  1971. if (!IS_SD_PRINTING)
  1972. {
  1973. custom_message = true;
  1974. custom_message_type = 1;
  1975. custom_message_state = (MESH_MEAS_NUM_X_POINTS * MESH_MEAS_NUM_Y_POINTS) + 10;
  1976. }
  1977. // Firstly check if we know where we are
  1978. if ( !( axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS] ) ){
  1979. // We don't know where we are! HOME!
  1980. // Push the commands to the front of the message queue in the reverse order!
  1981. // There shall be always enough space reserved for these commands.
  1982. repeatcommand_front(); // repeat G80 with all its parameters
  1983. enquecommand_front_P((PSTR("G28 W0")));
  1984. break;
  1985. }
  1986. mbl.reset();
  1987. // Reset baby stepping to zero, if the babystepping has already been loaded before. The babystepsTodo value will be
  1988. // consumed during the first movements following this statement.
  1989. #ifdef BABYSTEP_LOADZ_BY_PLANNER
  1990. shift_z(float(babystepLoadZ) / float(axis_steps_per_unit[Z_AXIS]));
  1991. #else
  1992. babystepsTodoZsubtract(babystepLoadZ);
  1993. #endif /* BABYSTEP_LOADZ_BY_PLANNER */
  1994. babystepLoadZ = 0;
  1995. // Cycle through all points and probe them
  1996. // First move up. During this first movement, the babystepping will be reverted.
  1997. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  1998. 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);
  1999. // The move to the first calibration point.
  2000. current_position[X_AXIS] = pgm_read_float(bed_ref_points);
  2001. current_position[Y_AXIS] = pgm_read_float(bed_ref_points+1);
  2002. world2machine_clamp(current_position[X_AXIS], current_position[Y_AXIS]);
  2003. // mbl.get_meas_xy(0, 0, current_position[X_AXIS], current_position[Y_AXIS], false);
  2004. 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);
  2005. // Wait until the move is finished.
  2006. st_synchronize();
  2007. int mesh_point = 0;
  2008. int ix = 0;
  2009. int iy = 0;
  2010. int XY_AXIS_FEEDRATE = homing_feedrate[X_AXIS]/20;
  2011. int Z_PROBE_FEEDRATE = homing_feedrate[Z_AXIS]/60;
  2012. int Z_LIFT_FEEDRATE = homing_feedrate[Z_AXIS]/40;
  2013. bool has_z = is_bed_z_jitter_data_valid();
  2014. setup_for_endstop_move();
  2015. const char *kill_message = NULL;
  2016. while (mesh_point != MESH_MEAS_NUM_X_POINTS * MESH_MEAS_NUM_Y_POINTS) {
  2017. // Get coords of a measuring point.
  2018. ix = mesh_point % MESH_MEAS_NUM_X_POINTS;
  2019. iy = mesh_point / MESH_MEAS_NUM_X_POINTS;
  2020. if (iy & 1) ix = (MESH_MEAS_NUM_X_POINTS - 1) - ix; // Zig zag
  2021. float z0 = 0.f;
  2022. if (has_z && mesh_point > 0) {
  2023. uint16_t z_offset_u = eeprom_read_word((uint16_t*)(EEPROM_BED_CALIBRATION_Z_JITTER + 2 * (ix + iy * 3 - 1)));
  2024. z0 = mbl.z_values[0][0] + *reinterpret_cast<int16_t*>(&z_offset_u) * 0.01;
  2025. #if 0
  2026. SERIAL_ECHOPGM("Bed leveling, point: ");
  2027. MYSERIAL.print(mesh_point);
  2028. SERIAL_ECHOPGM(", calibration z: ");
  2029. MYSERIAL.print(z0, 5);
  2030. SERIAL_ECHOLNPGM("");
  2031. #endif
  2032. }
  2033. // Move Z to proper distance
  2034. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  2035. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], Z_LIFT_FEEDRATE, active_extruder);
  2036. st_synchronize();
  2037. current_position[X_AXIS] = pgm_read_float(bed_ref_points+2*mesh_point);
  2038. current_position[Y_AXIS] = pgm_read_float(bed_ref_points+2*mesh_point+1);
  2039. world2machine_clamp(current_position[X_AXIS], current_position[Y_AXIS]);
  2040. // mbl.get_meas_xy(ix, iy, current_position[X_AXIS], current_position[Y_AXIS], false);
  2041. enable_endstops(false);
  2042. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], XY_AXIS_FEEDRATE, active_extruder);
  2043. st_synchronize();
  2044. // Go down until endstop is hit
  2045. const float Z_CALIBRATION_THRESHOLD = 1.f;
  2046. if (! find_bed_induction_sensor_point_z((has_z && mesh_point > 0) ? z0 - Z_CALIBRATION_THRESHOLD : -10.f)) {
  2047. kill_message = MSG_BED_LEVELING_FAILED_POINT_LOW;
  2048. break;
  2049. }
  2050. if (MESH_HOME_Z_SEARCH - current_position[Z_AXIS] < 0.1f) {
  2051. kill_message = MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED;
  2052. break;
  2053. }
  2054. if (has_z && fabs(z0 - current_position[Z_AXIS]) > Z_CALIBRATION_THRESHOLD) {
  2055. kill_message = MSG_BED_LEVELING_FAILED_POINT_HIGH;
  2056. break;
  2057. }
  2058. mbl.set_z(ix, iy, current_position[Z_AXIS]);
  2059. if (!IS_SD_PRINTING)
  2060. {
  2061. custom_message_state--;
  2062. }
  2063. mesh_point++;
  2064. }
  2065. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  2066. plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS],current_position[Z_AXIS] , current_position[E_AXIS], Z_LIFT_FEEDRATE, active_extruder);
  2067. if (mesh_point != MESH_MEAS_NUM_X_POINTS * MESH_MEAS_NUM_Y_POINTS) {
  2068. st_synchronize();
  2069. kill(kill_message);
  2070. }
  2071. clean_up_after_endstop_move();
  2072. // Apply Z height correction aka baby stepping before mesh bed leveing gets activated.
  2073. if(card.sdprinting || is_usb_printing )
  2074. {
  2075. if(eeprom_read_byte((unsigned char*)EEPROM_BABYSTEP_Z_SET) == 0x01)
  2076. {
  2077. // End of G80: Apply the baby stepping value.
  2078. EEPROM_read_B(EEPROM_BABYSTEP_Z,&babystepLoadZ);
  2079. #if 0
  2080. SERIAL_ECHO("Z baby step: ");
  2081. SERIAL_ECHO(babystepLoadZ);
  2082. SERIAL_ECHO(", current Z: ");
  2083. SERIAL_ECHO(current_position[Z_AXIS]);
  2084. SERIAL_ECHO("correction: ");
  2085. SERIAL_ECHO(float(babystepLoadZ) / float(axis_steps_per_unit[Z_AXIS]));
  2086. SERIAL_ECHOLN("");
  2087. #endif
  2088. #ifdef BABYSTEP_LOADZ_BY_PLANNER
  2089. shift_z(- float(babystepLoadZ) / float(axis_steps_per_unit[Z_AXIS]));
  2090. #else
  2091. babystepsTodoZadd(babystepLoadZ);
  2092. #endif /* BABYSTEP_LOADZ_BY_PLANNER */
  2093. }
  2094. }
  2095. bool eeprom_bed_correction_valid = eeprom_read_byte((unsigned char*)EEPROM_BED_CORRECTION_VALID) == 1;
  2096. for (uint8_t i = 0; i < 4; ++ i) {
  2097. unsigned char codes[4] = { 'L', 'R', 'F', 'B' };
  2098. long correction = 0;
  2099. if (code_seen(codes[i]))
  2100. correction = code_value_long();
  2101. else if (eeprom_bed_correction_valid) {
  2102. unsigned char *addr = (i < 2) ?
  2103. ((i == 0) ? (unsigned char*)EEPROM_BED_CORRECTION_LEFT : (unsigned char*)EEPROM_BED_CORRECTION_RIGHT) :
  2104. ((i == 2) ? (unsigned char*)EEPROM_BED_CORRECTION_FRONT : (unsigned char*)EEPROM_BED_CORRECTION_REAR);
  2105. correction = eeprom_read_int8(addr);
  2106. }
  2107. if (correction == 0)
  2108. continue;
  2109. float offset = float(correction) * 0.001f;
  2110. if (fabs(offset) > 0.101f) {
  2111. SERIAL_ERROR_START;
  2112. SERIAL_ECHOPGM("Excessive bed leveling correction: ");
  2113. SERIAL_ECHO(offset);
  2114. SERIAL_ECHOLNPGM(" microns");
  2115. } else {
  2116. switch (i) {
  2117. case 0:
  2118. for (uint8_t row = 0; row < 3; ++ row) {
  2119. mbl.z_values[row][1] += 0.5f * offset;
  2120. mbl.z_values[row][0] += offset;
  2121. }
  2122. break;
  2123. case 1:
  2124. for (uint8_t row = 0; row < 3; ++ row) {
  2125. mbl.z_values[row][1] += 0.5f * offset;
  2126. mbl.z_values[row][2] += offset;
  2127. }
  2128. break;
  2129. case 2:
  2130. for (uint8_t col = 0; col < 3; ++ col) {
  2131. mbl.z_values[1][col] += 0.5f * offset;
  2132. mbl.z_values[0][col] += offset;
  2133. }
  2134. break;
  2135. case 3:
  2136. for (uint8_t col = 0; col < 3; ++ col) {
  2137. mbl.z_values[1][col] += 0.5f * offset;
  2138. mbl.z_values[2][col] += offset;
  2139. }
  2140. break;
  2141. }
  2142. }
  2143. }
  2144. mbl.upsample_3x3();
  2145. mbl.active = 1;
  2146. current_position[X_AXIS] = X_MIN_POS+0.2;
  2147. current_position[Y_AXIS] = Y_MIN_POS+0.2;
  2148. current_position[Z_AXIS] = Z_MIN_POS;
  2149. world2machine_clamp(current_position[X_AXIS], current_position[Y_AXIS]);
  2150. plan_buffer_line(current_position[X_AXIS], current_position[X_AXIS], current_position[Z_AXIS], current_position[E_AXIS], XY_AXIS_FEEDRATE, active_extruder);
  2151. st_synchronize();
  2152. }
  2153. break;
  2154. /**
  2155. * G81: Print mesh bed leveling status and bed profile if activated
  2156. */
  2157. case 81:
  2158. if (mbl.active) {
  2159. SERIAL_PROTOCOLPGM("Num X,Y: ");
  2160. SERIAL_PROTOCOL(MESH_NUM_X_POINTS);
  2161. SERIAL_PROTOCOLPGM(",");
  2162. SERIAL_PROTOCOL(MESH_NUM_Y_POINTS);
  2163. SERIAL_PROTOCOLPGM("\nZ search height: ");
  2164. SERIAL_PROTOCOL(MESH_HOME_Z_SEARCH);
  2165. SERIAL_PROTOCOLLNPGM("\nMeasured points:");
  2166. for (int y = MESH_NUM_Y_POINTS-1; y >= 0; y--) {
  2167. for (int x = 0; x < MESH_NUM_X_POINTS; x++) {
  2168. SERIAL_PROTOCOLPGM(" ");
  2169. SERIAL_PROTOCOL_F(mbl.z_values[y][x], 5);
  2170. }
  2171. SERIAL_PROTOCOLPGM("\n");
  2172. }
  2173. }
  2174. else
  2175. SERIAL_PROTOCOLLNPGM("Mesh bed leveling not active.");
  2176. break;
  2177. /**
  2178. * G82: Single Z probe at current location
  2179. *
  2180. * WARNING! USE WITH CAUTION! If you'll try to probe where is no leveling pad, nasty things can happen!
  2181. *
  2182. */
  2183. case 82:
  2184. SERIAL_PROTOCOLLNPGM("Finding bed ");
  2185. setup_for_endstop_move();
  2186. find_bed_induction_sensor_point_z();
  2187. clean_up_after_endstop_move();
  2188. SERIAL_PROTOCOLPGM("Bed found at: ");
  2189. SERIAL_PROTOCOL_F(current_position[Z_AXIS], 5);
  2190. SERIAL_PROTOCOLPGM("\n");
  2191. break;
  2192. /**
  2193. * G83: Prusa3D specific: Babystep in Z and store to EEPROM
  2194. */
  2195. case 83:
  2196. {
  2197. int babystepz = code_seen('S') ? code_value() : 0;
  2198. int BabyPosition = code_seen('P') ? code_value() : 0;
  2199. if (babystepz != 0) {
  2200. //FIXME Vojtech: What shall be the index of the axis Z: 3 or 4?
  2201. // Is the axis indexed starting with zero or one?
  2202. if (BabyPosition > 4) {
  2203. SERIAL_PROTOCOLLNPGM("Index out of bounds");
  2204. }else{
  2205. // Save it to the eeprom
  2206. babystepLoadZ = babystepz;
  2207. EEPROM_save_B(EEPROM_BABYSTEP_Z0+(BabyPosition*2),&babystepLoadZ);
  2208. // adjust the Z
  2209. babystepsTodoZadd(babystepLoadZ);
  2210. }
  2211. }
  2212. }
  2213. break;
  2214. /**
  2215. * G84: Prusa3D specific: UNDO Babystep Z (move Z axis back)
  2216. */
  2217. case 84:
  2218. babystepsTodoZsubtract(babystepLoadZ);
  2219. // babystepLoadZ = 0;
  2220. break;
  2221. /**
  2222. * G85: Prusa3D specific: Pick best babystep
  2223. */
  2224. case 85:
  2225. lcd_pick_babystep();
  2226. break;
  2227. /**
  2228. * G86: Prusa3D specific: Disable babystep correction after home.
  2229. * This G-code will be performed at the start of a calibration script.
  2230. */
  2231. case 86:
  2232. eeprom_write_byte((unsigned char*)EEPROM_BABYSTEP_Z_SET, 0xFF);
  2233. break;
  2234. /**
  2235. * G87: Prusa3D specific: Enable babystep correction after home
  2236. * This G-code will be performed at the end of a calibration script.
  2237. */
  2238. case 87:
  2239. eeprom_write_byte((unsigned char*)EEPROM_BABYSTEP_Z_SET, 0x01);
  2240. break;
  2241. case 88:
  2242. break;
  2243. #endif // ENABLE_MESH_BED_LEVELING
  2244. case 90: // G90
  2245. relative_mode = false;
  2246. break;
  2247. case 91: // G91
  2248. relative_mode = true;
  2249. break;
  2250. case 92: // G92
  2251. if(!code_seen(axis_codes[E_AXIS]))
  2252. st_synchronize();
  2253. for(int8_t i=0; i < NUM_AXIS; i++) {
  2254. if(code_seen(axis_codes[i])) {
  2255. if(i == E_AXIS) {
  2256. current_position[i] = code_value();
  2257. plan_set_e_position(current_position[E_AXIS]);
  2258. }
  2259. else {
  2260. current_position[i] = code_value()+add_homing[i];
  2261. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  2262. }
  2263. }
  2264. }
  2265. break;
  2266. case 98:
  2267. farm_no = 21;
  2268. EEPROM_save_B(EEPROM_FARM_MODE, &farm_no);
  2269. farm_mode = true;
  2270. break;
  2271. case 99:
  2272. farm_no = 0;
  2273. EEPROM_save_B(EEPROM_FARM_MODE, &farm_no);
  2274. farm_mode = false;
  2275. break;
  2276. }
  2277. } // end if(code_seen('G'))
  2278. else if(code_seen('M'))
  2279. {
  2280. switch( (int)code_value() )
  2281. {
  2282. #ifdef ULTIPANEL
  2283. case 0: // M0 - Unconditional stop - Wait for user button press on LCD
  2284. case 1: // M1 - Conditional stop - Wait for user button press on LCD
  2285. {
  2286. char *src = strchr_pointer + 2;
  2287. codenum = 0;
  2288. bool hasP = false, hasS = false;
  2289. if (code_seen('P')) {
  2290. codenum = code_value(); // milliseconds to wait
  2291. hasP = codenum > 0;
  2292. }
  2293. if (code_seen('S')) {
  2294. codenum = code_value() * 1000; // seconds to wait
  2295. hasS = codenum > 0;
  2296. }
  2297. starpos = strchr(src, '*');
  2298. if (starpos != NULL) *(starpos) = '\0';
  2299. while (*src == ' ') ++src;
  2300. if (!hasP && !hasS && *src != '\0') {
  2301. lcd_setstatus(src);
  2302. } else {
  2303. LCD_MESSAGERPGM(MSG_USERWAIT);
  2304. }
  2305. lcd_ignore_click();
  2306. st_synchronize();
  2307. previous_millis_cmd = millis();
  2308. if (codenum > 0){
  2309. codenum += millis(); // keep track of when we started waiting
  2310. while(millis() < codenum && !lcd_clicked()){
  2311. manage_heater();
  2312. manage_inactivity();
  2313. lcd_update();
  2314. }
  2315. lcd_ignore_click(false);
  2316. }else{
  2317. if (!lcd_detected())
  2318. break;
  2319. while(!lcd_clicked()){
  2320. manage_heater();
  2321. manage_inactivity();
  2322. lcd_update();
  2323. }
  2324. }
  2325. if (IS_SD_PRINTING)
  2326. LCD_MESSAGERPGM(MSG_RESUMING);
  2327. else
  2328. LCD_MESSAGERPGM(WELCOME_MSG);
  2329. }
  2330. break;
  2331. #endif
  2332. case 17:
  2333. LCD_MESSAGERPGM(MSG_NO_MOVE);
  2334. enable_x();
  2335. enable_y();
  2336. enable_z();
  2337. enable_e0();
  2338. enable_e1();
  2339. enable_e2();
  2340. break;
  2341. #ifdef SDSUPPORT
  2342. case 20: // M20 - list SD card
  2343. SERIAL_PROTOCOLLNRPGM(MSG_BEGIN_FILE_LIST);
  2344. card.ls();
  2345. SERIAL_PROTOCOLLNRPGM(MSG_END_FILE_LIST);
  2346. break;
  2347. case 21: // M21 - init SD card
  2348. card.initsd();
  2349. break;
  2350. case 22: //M22 - release SD card
  2351. card.release();
  2352. break;
  2353. case 23: //M23 - Select file
  2354. starpos = (strchr(strchr_pointer + 4,'*'));
  2355. if(starpos!=NULL)
  2356. *(starpos)='\0';
  2357. card.openFile(strchr_pointer + 4,true);
  2358. break;
  2359. case 24: //M24 - Start SD print
  2360. card.startFileprint();
  2361. starttime=millis();
  2362. break;
  2363. case 25: //M25 - Pause SD print
  2364. card.pauseSDPrint();
  2365. break;
  2366. case 26: //M26 - Set SD index
  2367. if(card.cardOK && code_seen('S')) {
  2368. card.setIndex(code_value_long());
  2369. }
  2370. break;
  2371. case 27: //M27 - Get SD status
  2372. card.getStatus();
  2373. break;
  2374. case 28: //M28 - Start SD write
  2375. starpos = (strchr(strchr_pointer + 4,'*'));
  2376. if(starpos != NULL){
  2377. char* npos = strchr(CMDBUFFER_CURRENT_STRING, 'N');
  2378. strchr_pointer = strchr(npos,' ') + 1;
  2379. *(starpos) = '\0';
  2380. }
  2381. card.openFile(strchr_pointer+4,false);
  2382. break;
  2383. case 29: //M29 - Stop SD write
  2384. //processed in write to file routine above
  2385. //card,saving = false;
  2386. break;
  2387. case 30: //M30 <filename> Delete File
  2388. if (card.cardOK){
  2389. card.closefile();
  2390. starpos = (strchr(strchr_pointer + 4,'*'));
  2391. if(starpos != NULL){
  2392. char* npos = strchr(CMDBUFFER_CURRENT_STRING, 'N');
  2393. strchr_pointer = strchr(npos,' ') + 1;
  2394. *(starpos) = '\0';
  2395. }
  2396. card.removeFile(strchr_pointer + 4);
  2397. }
  2398. break;
  2399. case 32: //M32 - Select file and start SD print
  2400. {
  2401. if(card.sdprinting) {
  2402. st_synchronize();
  2403. }
  2404. starpos = (strchr(strchr_pointer + 4,'*'));
  2405. char* namestartpos = (strchr(strchr_pointer + 4,'!')); //find ! to indicate filename string start.
  2406. if(namestartpos==NULL)
  2407. {
  2408. namestartpos=strchr_pointer + 4; //default name position, 4 letters after the M
  2409. }
  2410. else
  2411. namestartpos++; //to skip the '!'
  2412. if(starpos!=NULL)
  2413. *(starpos)='\0';
  2414. bool call_procedure=(code_seen('P'));
  2415. if(strchr_pointer>namestartpos)
  2416. call_procedure=false; //false alert, 'P' found within filename
  2417. if( card.cardOK )
  2418. {
  2419. card.openFile(namestartpos,true,!call_procedure);
  2420. if(code_seen('S'))
  2421. if(strchr_pointer<namestartpos) //only if "S" is occuring _before_ the filename
  2422. card.setIndex(code_value_long());
  2423. card.startFileprint();
  2424. if(!call_procedure)
  2425. starttime=millis(); //procedure calls count as normal print time.
  2426. }
  2427. } break;
  2428. case 928: //M928 - Start SD write
  2429. starpos = (strchr(strchr_pointer + 5,'*'));
  2430. if(starpos != NULL){
  2431. char* npos = strchr(CMDBUFFER_CURRENT_STRING, 'N');
  2432. strchr_pointer = strchr(npos,' ') + 1;
  2433. *(starpos) = '\0';
  2434. }
  2435. card.openLogFile(strchr_pointer+5);
  2436. break;
  2437. #endif //SDSUPPORT
  2438. case 31: //M31 take time since the start of the SD print or an M109 command
  2439. {
  2440. stoptime=millis();
  2441. char time[30];
  2442. unsigned long t=(stoptime-starttime)/1000;
  2443. int sec,min;
  2444. min=t/60;
  2445. sec=t%60;
  2446. sprintf_P(time, PSTR("%i min, %i sec"), min, sec);
  2447. SERIAL_ECHO_START;
  2448. SERIAL_ECHOLN(time);
  2449. lcd_setstatus(time);
  2450. autotempShutdown();
  2451. }
  2452. break;
  2453. case 42: //M42 -Change pin status via gcode
  2454. if (code_seen('S'))
  2455. {
  2456. int pin_status = code_value();
  2457. int pin_number = LED_PIN;
  2458. if (code_seen('P') && pin_status >= 0 && pin_status <= 255)
  2459. pin_number = code_value();
  2460. for(int8_t i = 0; i < (int8_t)(sizeof(sensitive_pins)/sizeof(int)); i++)
  2461. {
  2462. if (sensitive_pins[i] == pin_number)
  2463. {
  2464. pin_number = -1;
  2465. break;
  2466. }
  2467. }
  2468. #if defined(FAN_PIN) && FAN_PIN > -1
  2469. if (pin_number == FAN_PIN)
  2470. fanSpeed = pin_status;
  2471. #endif
  2472. if (pin_number > -1)
  2473. {
  2474. pinMode(pin_number, OUTPUT);
  2475. digitalWrite(pin_number, pin_status);
  2476. analogWrite(pin_number, pin_status);
  2477. }
  2478. }
  2479. break;
  2480. case 44: // M44: Prusa3D: Reset the bed skew and offset calibration.
  2481. // Reset the skew and offset in both RAM and EEPROM.
  2482. reset_bed_offset_and_skew();
  2483. // Reset world2machine_rotation_and_skew and world2machine_shift, therefore
  2484. // the planner will not perform any adjustments in the XY plane.
  2485. // Wait for the motors to stop and update the current position with the absolute values.
  2486. world2machine_revert_to_uncorrected();
  2487. break;
  2488. case 45: // M45: Prusa3D: bed skew and offset with manual Z up
  2489. {
  2490. // Disable the default update procedure of the display. We will do a modal dialog.
  2491. lcd_update_enable(false);
  2492. // Let the planner use the uncorrected coordinates.
  2493. mbl.reset();
  2494. // Reset world2machine_rotation_and_skew and world2machine_shift, therefore
  2495. // the planner will not perform any adjustments in the XY plane.
  2496. // Wait for the motors to stop and update the current position with the absolute values.
  2497. world2machine_revert_to_uncorrected();
  2498. // Let the user move the Z axes up to the end stoppers.
  2499. if (lcd_calibrate_z_end_stop_manual()) {
  2500. refresh_cmd_timeout();
  2501. // Move the print head close to the bed.
  2502. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  2503. 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);
  2504. st_synchronize();
  2505. // Home in the XY plane.
  2506. set_destination_to_current();
  2507. setup_for_endstop_move();
  2508. home_xy();
  2509. int8_t verbosity_level = 0;
  2510. if (code_seen('V')) {
  2511. // Just 'V' without a number counts as V1.
  2512. char c = strchr_pointer[1];
  2513. verbosity_level = (c == ' ' || c == '\t' || c == 0) ? 1 : code_value_short();
  2514. }
  2515. BedSkewOffsetDetectionResultType result = find_bed_offset_and_skew(verbosity_level);
  2516. uint8_t point_too_far_mask = 0;
  2517. clean_up_after_endstop_move();
  2518. // Print head up.
  2519. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  2520. 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);
  2521. st_synchronize();
  2522. if (result >= 0) {
  2523. // Second half: The fine adjustment.
  2524. // Let the planner use the uncorrected coordinates.
  2525. mbl.reset();
  2526. world2machine_reset();
  2527. // Home in the XY plane.
  2528. setup_for_endstop_move();
  2529. home_xy();
  2530. result = improve_bed_offset_and_skew(1, verbosity_level, point_too_far_mask);
  2531. clean_up_after_endstop_move();
  2532. // Print head up.
  2533. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  2534. 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);
  2535. st_synchronize();
  2536. }
  2537. lcd_bed_calibration_show_result(result, point_too_far_mask);
  2538. } else {
  2539. // Timeouted.
  2540. }
  2541. lcd_update_enable(true);
  2542. lcd_implementation_clear();
  2543. // lcd_return_to_status();
  2544. lcd_update();
  2545. break;
  2546. }
  2547. /*
  2548. case 46:
  2549. {
  2550. // M46: Prusa3D: Show the assigned IP address.
  2551. uint8_t ip[4];
  2552. bool hasIP = card.ToshibaFlashAir_GetIP(ip);
  2553. if (hasIP) {
  2554. SERIAL_ECHOPGM("Toshiba FlashAir current IP: ");
  2555. SERIAL_ECHO(int(ip[0]));
  2556. SERIAL_ECHOPGM(".");
  2557. SERIAL_ECHO(int(ip[1]));
  2558. SERIAL_ECHOPGM(".");
  2559. SERIAL_ECHO(int(ip[2]));
  2560. SERIAL_ECHOPGM(".");
  2561. SERIAL_ECHO(int(ip[3]));
  2562. SERIAL_ECHOLNPGM("");
  2563. } else {
  2564. SERIAL_ECHOLNPGM("Toshiba FlashAir GetIP failed");
  2565. }
  2566. break;
  2567. }
  2568. */
  2569. case 47:
  2570. // M47: Prusa3D: Show end stops dialog on the display.
  2571. lcd_diag_show_end_stops();
  2572. break;
  2573. #if 0
  2574. case 48: // M48: scan the bed induction sensor points, print the sensor trigger coordinates to the serial line for visualization on the PC.
  2575. {
  2576. // Disable the default update procedure of the display. We will do a modal dialog.
  2577. lcd_update_enable(false);
  2578. // Let the planner use the uncorrected coordinates.
  2579. mbl.reset();
  2580. // Reset world2machine_rotation_and_skew and world2machine_shift, therefore
  2581. // the planner will not perform any adjustments in the XY plane.
  2582. // Wait for the motors to stop and update the current position with the absolute values.
  2583. world2machine_revert_to_uncorrected();
  2584. // Move the print head close to the bed.
  2585. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  2586. 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);
  2587. st_synchronize();
  2588. // Home in the XY plane.
  2589. set_destination_to_current();
  2590. setup_for_endstop_move();
  2591. home_xy();
  2592. int8_t verbosity_level = 0;
  2593. if (code_seen('V')) {
  2594. // Just 'V' without a number counts as V1.
  2595. char c = strchr_pointer[1];
  2596. verbosity_level = (c == ' ' || c == '\t' || c == 0) ? 1 : code_value_short();
  2597. }
  2598. bool success = scan_bed_induction_points(verbosity_level);
  2599. clean_up_after_endstop_move();
  2600. // Print head up.
  2601. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
  2602. 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);
  2603. st_synchronize();
  2604. lcd_update_enable(true);
  2605. lcd_implementation_clear();
  2606. // lcd_return_to_status();
  2607. lcd_update();
  2608. break;
  2609. }
  2610. #endif
  2611. // M48 Z-Probe repeatability measurement function.
  2612. //
  2613. // 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>
  2614. //
  2615. // This function assumes the bed has been homed. Specificaly, that a G28 command
  2616. // as been issued prior to invoking the M48 Z-Probe repeatability measurement function.
  2617. // Any information generated by a prior G29 Bed leveling command will be lost and need to be
  2618. // regenerated.
  2619. //
  2620. // The number of samples will default to 10 if not specified. You can use upper or lower case
  2621. // letters for any of the options EXCEPT n. n must be in lower case because Marlin uses a capital
  2622. // N for its communication protocol and will get horribly confused if you send it a capital N.
  2623. //
  2624. #ifdef ENABLE_AUTO_BED_LEVELING
  2625. #ifdef Z_PROBE_REPEATABILITY_TEST
  2626. case 48: // M48 Z-Probe repeatability
  2627. {
  2628. #if Z_MIN_PIN == -1
  2629. #error "You must have a Z_MIN endstop in order to enable calculation of Z-Probe repeatability."
  2630. #endif
  2631. double sum=0.0;
  2632. double mean=0.0;
  2633. double sigma=0.0;
  2634. double sample_set[50];
  2635. int verbose_level=1, n=0, j, n_samples = 10, n_legs=0;
  2636. double X_current, Y_current, Z_current;
  2637. double X_probe_location, Y_probe_location, Z_start_location, ext_position;
  2638. if (code_seen('V') || code_seen('v')) {
  2639. verbose_level = code_value();
  2640. if (verbose_level<0 || verbose_level>4 ) {
  2641. SERIAL_PROTOCOLPGM("?Verbose Level not plausable.\n");
  2642. goto Sigma_Exit;
  2643. }
  2644. }
  2645. if (verbose_level > 0) {
  2646. SERIAL_PROTOCOLPGM("M48 Z-Probe Repeatability test. Version 2.00\n");
  2647. SERIAL_PROTOCOLPGM("Full support at: http://3dprintboard.com/forum.php\n");
  2648. }
  2649. if (code_seen('n')) {
  2650. n_samples = code_value();
  2651. if (n_samples<4 || n_samples>50 ) {
  2652. SERIAL_PROTOCOLPGM("?Specified sample size not plausable.\n");
  2653. goto Sigma_Exit;
  2654. }
  2655. }
  2656. X_current = X_probe_location = st_get_position_mm(X_AXIS);
  2657. Y_current = Y_probe_location = st_get_position_mm(Y_AXIS);
  2658. Z_current = st_get_position_mm(Z_AXIS);
  2659. Z_start_location = st_get_position_mm(Z_AXIS) + Z_RAISE_BEFORE_PROBING;
  2660. ext_position = st_get_position_mm(E_AXIS);
  2661. if (code_seen('X') || code_seen('x') ) {
  2662. X_probe_location = code_value() - X_PROBE_OFFSET_FROM_EXTRUDER;
  2663. if (X_probe_location<X_MIN_POS || X_probe_location>X_MAX_POS ) {
  2664. SERIAL_PROTOCOLPGM("?Specified X position out of range.\n");
  2665. goto Sigma_Exit;
  2666. }
  2667. }
  2668. if (code_seen('Y') || code_seen('y') ) {
  2669. Y_probe_location = code_value() - Y_PROBE_OFFSET_FROM_EXTRUDER;
  2670. if (Y_probe_location<Y_MIN_POS || Y_probe_location>Y_MAX_POS ) {
  2671. SERIAL_PROTOCOLPGM("?Specified Y position out of range.\n");
  2672. goto Sigma_Exit;
  2673. }
  2674. }
  2675. if (code_seen('L') || code_seen('l') ) {
  2676. n_legs = code_value();
  2677. if ( n_legs==1 )
  2678. n_legs = 2;
  2679. if ( n_legs<0 || n_legs>15 ) {
  2680. SERIAL_PROTOCOLPGM("?Specified number of legs in movement not plausable.\n");
  2681. goto Sigma_Exit;
  2682. }
  2683. }
  2684. //
  2685. // Do all the preliminary setup work. First raise the probe.
  2686. //
  2687. st_synchronize();
  2688. plan_bed_level_matrix.set_to_identity();
  2689. plan_buffer_line( X_current, Y_current, Z_start_location,
  2690. ext_position,
  2691. homing_feedrate[Z_AXIS]/60,
  2692. active_extruder);
  2693. st_synchronize();
  2694. //
  2695. // Now get everything to the specified probe point So we can safely do a probe to
  2696. // get us close to the bed. If the Z-Axis is far from the bed, we don't want to
  2697. // use that as a starting point for each probe.
  2698. //
  2699. if (verbose_level > 2)
  2700. SERIAL_PROTOCOL("Positioning probe for the test.\n");
  2701. plan_buffer_line( X_probe_location, Y_probe_location, Z_start_location,
  2702. ext_position,
  2703. homing_feedrate[X_AXIS]/60,
  2704. active_extruder);
  2705. st_synchronize();
  2706. current_position[X_AXIS] = X_current = st_get_position_mm(X_AXIS);
  2707. current_position[Y_AXIS] = Y_current = st_get_position_mm(Y_AXIS);
  2708. current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS);
  2709. current_position[E_AXIS] = ext_position = st_get_position_mm(E_AXIS);
  2710. //
  2711. // OK, do the inital probe to get us close to the bed.
  2712. // Then retrace the right amount and use that in subsequent probes
  2713. //
  2714. setup_for_endstop_move();
  2715. run_z_probe();
  2716. current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS);
  2717. Z_start_location = st_get_position_mm(Z_AXIS) + Z_RAISE_BEFORE_PROBING;
  2718. plan_buffer_line( X_probe_location, Y_probe_location, Z_start_location,
  2719. ext_position,
  2720. homing_feedrate[X_AXIS]/60,
  2721. active_extruder);
  2722. st_synchronize();
  2723. current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS);
  2724. for( n=0; n<n_samples; n++) {
  2725. do_blocking_move_to( X_probe_location, Y_probe_location, Z_start_location); // Make sure we are at the probe location
  2726. if ( n_legs) {
  2727. double radius=0.0, theta=0.0, x_sweep, y_sweep;
  2728. int rotational_direction, l;
  2729. rotational_direction = (unsigned long) millis() & 0x0001; // clockwise or counter clockwise
  2730. radius = (unsigned long) millis() % (long) (X_MAX_LENGTH/4); // limit how far out to go
  2731. theta = (float) ((unsigned long) millis() % (long) 360) / (360./(2*3.1415926)); // turn into radians
  2732. //SERIAL_ECHOPAIR("starting radius: ",radius);
  2733. //SERIAL_ECHOPAIR(" theta: ",theta);
  2734. //SERIAL_ECHOPAIR(" direction: ",rotational_direction);
  2735. //SERIAL_PROTOCOLLNPGM("");
  2736. for( l=0; l<n_legs-1; l++) {
  2737. if (rotational_direction==1)
  2738. theta += (float) ((unsigned long) millis() % (long) 20) / (360.0/(2*3.1415926)); // turn into radians
  2739. else
  2740. theta -= (float) ((unsigned long) millis() % (long) 20) / (360.0/(2*3.1415926)); // turn into radians
  2741. radius += (float) ( ((long) ((unsigned long) millis() % (long) 10)) - 5);
  2742. if ( radius<0.0 )
  2743. radius = -radius;
  2744. X_current = X_probe_location + cos(theta) * radius;
  2745. Y_current = Y_probe_location + sin(theta) * radius;
  2746. if ( X_current<X_MIN_POS) // Make sure our X & Y are sane
  2747. X_current = X_MIN_POS;
  2748. if ( X_current>X_MAX_POS)
  2749. X_current = X_MAX_POS;
  2750. if ( Y_current<Y_MIN_POS) // Make sure our X & Y are sane
  2751. Y_current = Y_MIN_POS;
  2752. if ( Y_current>Y_MAX_POS)
  2753. Y_current = Y_MAX_POS;
  2754. if (verbose_level>3 ) {
  2755. SERIAL_ECHOPAIR("x: ", X_current);
  2756. SERIAL_ECHOPAIR("y: ", Y_current);
  2757. SERIAL_PROTOCOLLNPGM("");
  2758. }
  2759. do_blocking_move_to( X_current, Y_current, Z_current );
  2760. }
  2761. do_blocking_move_to( X_probe_location, Y_probe_location, Z_start_location); // Go back to the probe location
  2762. }
  2763. setup_for_endstop_move();
  2764. run_z_probe();
  2765. sample_set[n] = current_position[Z_AXIS];
  2766. //
  2767. // Get the current mean for the data points we have so far
  2768. //
  2769. sum=0.0;
  2770. for( j=0; j<=n; j++) {
  2771. sum = sum + sample_set[j];
  2772. }
  2773. mean = sum / (double (n+1));
  2774. //
  2775. // Now, use that mean to calculate the standard deviation for the
  2776. // data points we have so far
  2777. //
  2778. sum=0.0;
  2779. for( j=0; j<=n; j++) {
  2780. sum = sum + (sample_set[j]-mean) * (sample_set[j]-mean);
  2781. }
  2782. sigma = sqrt( sum / (double (n+1)) );
  2783. if (verbose_level > 1) {
  2784. SERIAL_PROTOCOL(n+1);
  2785. SERIAL_PROTOCOL(" of ");
  2786. SERIAL_PROTOCOL(n_samples);
  2787. SERIAL_PROTOCOLPGM(" z: ");
  2788. SERIAL_PROTOCOL_F(current_position[Z_AXIS], 6);
  2789. }
  2790. if (verbose_level > 2) {
  2791. SERIAL_PROTOCOL(" mean: ");
  2792. SERIAL_PROTOCOL_F(mean,6);
  2793. SERIAL_PROTOCOL(" sigma: ");
  2794. SERIAL_PROTOCOL_F(sigma,6);
  2795. }
  2796. if (verbose_level > 0)
  2797. SERIAL_PROTOCOLPGM("\n");
  2798. plan_buffer_line( X_probe_location, Y_probe_location, Z_start_location,
  2799. current_position[E_AXIS], homing_feedrate[Z_AXIS]/60, active_extruder);
  2800. st_synchronize();
  2801. }
  2802. delay(1000);
  2803. clean_up_after_endstop_move();
  2804. // enable_endstops(true);
  2805. if (verbose_level > 0) {
  2806. SERIAL_PROTOCOLPGM("Mean: ");
  2807. SERIAL_PROTOCOL_F(mean, 6);
  2808. SERIAL_PROTOCOLPGM("\n");
  2809. }
  2810. SERIAL_PROTOCOLPGM("Standard Deviation: ");
  2811. SERIAL_PROTOCOL_F(sigma, 6);
  2812. SERIAL_PROTOCOLPGM("\n\n");
  2813. Sigma_Exit:
  2814. break;
  2815. }
  2816. #endif // Z_PROBE_REPEATABILITY_TEST
  2817. #endif // ENABLE_AUTO_BED_LEVELING
  2818. case 104: // M104
  2819. if(setTargetedHotend(104)){
  2820. break;
  2821. }
  2822. if (code_seen('S')) setTargetHotend(code_value(), tmp_extruder);
  2823. setWatch();
  2824. break;
  2825. case 112: // M112 -Emergency Stop
  2826. kill();
  2827. break;
  2828. case 140: // M140 set bed temp
  2829. if (code_seen('S')) setTargetBed(code_value());
  2830. break;
  2831. case 105 : // M105
  2832. if(setTargetedHotend(105)){
  2833. break;
  2834. }
  2835. #if defined(TEMP_0_PIN) && TEMP_0_PIN > -1
  2836. SERIAL_PROTOCOLPGM("ok T:");
  2837. SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
  2838. SERIAL_PROTOCOLPGM(" /");
  2839. SERIAL_PROTOCOL_F(degTargetHotend(tmp_extruder),1);
  2840. #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
  2841. SERIAL_PROTOCOLPGM(" B:");
  2842. SERIAL_PROTOCOL_F(degBed(),1);
  2843. SERIAL_PROTOCOLPGM(" /");
  2844. SERIAL_PROTOCOL_F(degTargetBed(),1);
  2845. #endif //TEMP_BED_PIN
  2846. for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
  2847. SERIAL_PROTOCOLPGM(" T");
  2848. SERIAL_PROTOCOL(cur_extruder);
  2849. SERIAL_PROTOCOLPGM(":");
  2850. SERIAL_PROTOCOL_F(degHotend(cur_extruder),1);
  2851. SERIAL_PROTOCOLPGM(" /");
  2852. SERIAL_PROTOCOL_F(degTargetHotend(cur_extruder),1);
  2853. }
  2854. #else
  2855. SERIAL_ERROR_START;
  2856. SERIAL_ERRORLNRPGM(MSG_ERR_NO_THERMISTORS);
  2857. #endif
  2858. SERIAL_PROTOCOLPGM(" @:");
  2859. #ifdef EXTRUDER_WATTS
  2860. SERIAL_PROTOCOL((EXTRUDER_WATTS * getHeaterPower(tmp_extruder))/127);
  2861. SERIAL_PROTOCOLPGM("W");
  2862. #else
  2863. SERIAL_PROTOCOL(getHeaterPower(tmp_extruder));
  2864. #endif
  2865. SERIAL_PROTOCOLPGM(" B@:");
  2866. #ifdef BED_WATTS
  2867. SERIAL_PROTOCOL((BED_WATTS * getHeaterPower(-1))/127);
  2868. SERIAL_PROTOCOLPGM("W");
  2869. #else
  2870. SERIAL_PROTOCOL(getHeaterPower(-1));
  2871. #endif
  2872. #ifdef SHOW_TEMP_ADC_VALUES
  2873. #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
  2874. SERIAL_PROTOCOLPGM(" ADC B:");
  2875. SERIAL_PROTOCOL_F(degBed(),1);
  2876. SERIAL_PROTOCOLPGM("C->");
  2877. SERIAL_PROTOCOL_F(rawBedTemp()/OVERSAMPLENR,0);
  2878. #endif
  2879. for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
  2880. SERIAL_PROTOCOLPGM(" T");
  2881. SERIAL_PROTOCOL(cur_extruder);
  2882. SERIAL_PROTOCOLPGM(":");
  2883. SERIAL_PROTOCOL_F(degHotend(cur_extruder),1);
  2884. SERIAL_PROTOCOLPGM("C->");
  2885. SERIAL_PROTOCOL_F(rawHotendTemp(cur_extruder)/OVERSAMPLENR,0);
  2886. }
  2887. #endif
  2888. SERIAL_PROTOCOLLN("");
  2889. return;
  2890. break;
  2891. case 109:
  2892. {// M109 - Wait for extruder heater to reach target.
  2893. if(setTargetedHotend(109)){
  2894. break;
  2895. }
  2896. LCD_MESSAGERPGM(MSG_HEATING);
  2897. heating_status = 1;
  2898. if (farm_mode) { prusa_statistics(1); };
  2899. #ifdef AUTOTEMP
  2900. autotemp_enabled=false;
  2901. #endif
  2902. if (code_seen('S')) {
  2903. setTargetHotend(code_value(), tmp_extruder);
  2904. CooldownNoWait = true;
  2905. } else if (code_seen('R')) {
  2906. setTargetHotend(code_value(), tmp_extruder);
  2907. CooldownNoWait = false;
  2908. }
  2909. #ifdef AUTOTEMP
  2910. if (code_seen('S')) autotemp_min=code_value();
  2911. if (code_seen('B')) autotemp_max=code_value();
  2912. if (code_seen('F'))
  2913. {
  2914. autotemp_factor=code_value();
  2915. autotemp_enabled=true;
  2916. }
  2917. #endif
  2918. setWatch();
  2919. codenum = millis();
  2920. /* See if we are heating up or cooling down */
  2921. target_direction = isHeatingHotend(tmp_extruder); // true if heating, false if cooling
  2922. cancel_heatup = false;
  2923. #ifdef TEMP_RESIDENCY_TIME
  2924. long residencyStart;
  2925. residencyStart = -1;
  2926. /* continue to loop until we have reached the target temp
  2927. _and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */
  2928. while((!cancel_heatup)&&((residencyStart == -1) ||
  2929. (residencyStart >= 0 && (((unsigned int) (millis() - residencyStart)) < (TEMP_RESIDENCY_TIME * 1000UL)))) ) {
  2930. #else
  2931. while ( target_direction ? (isHeatingHotend(tmp_extruder)) : (isCoolingHotend(tmp_extruder)&&(CooldownNoWait==false)) ) {
  2932. #endif //TEMP_RESIDENCY_TIME
  2933. if( (millis() - codenum) > 1000UL )
  2934. { //Print Temp Reading and remaining time every 1 second while heating up/cooling down
  2935. SERIAL_PROTOCOLPGM("T:");
  2936. SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
  2937. SERIAL_PROTOCOLPGM(" E:");
  2938. SERIAL_PROTOCOL((int)tmp_extruder);
  2939. #ifdef TEMP_RESIDENCY_TIME
  2940. SERIAL_PROTOCOLPGM(" W:");
  2941. if(residencyStart > -1)
  2942. {
  2943. codenum = ((TEMP_RESIDENCY_TIME * 1000UL) - (millis() - residencyStart)) / 1000UL;
  2944. SERIAL_PROTOCOLLN( codenum );
  2945. }
  2946. else
  2947. {
  2948. SERIAL_PROTOCOLLN( "?" );
  2949. }
  2950. #else
  2951. SERIAL_PROTOCOLLN("");
  2952. #endif
  2953. codenum = millis();
  2954. }
  2955. manage_heater();
  2956. manage_inactivity();
  2957. lcd_update();
  2958. #ifdef TEMP_RESIDENCY_TIME
  2959. /* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
  2960. or when current temp falls outside the hysteresis after target temp was reached */
  2961. if ((residencyStart == -1 && target_direction && (degHotend(tmp_extruder) >= (degTargetHotend(tmp_extruder)-TEMP_WINDOW))) ||
  2962. (residencyStart == -1 && !target_direction && (degHotend(tmp_extruder) <= (degTargetHotend(tmp_extruder)+TEMP_WINDOW))) ||
  2963. (residencyStart > -1 && labs(degHotend(tmp_extruder) - degTargetHotend(tmp_extruder)) > TEMP_HYSTERESIS) )
  2964. {
  2965. residencyStart = millis();
  2966. }
  2967. #endif //TEMP_RESIDENCY_TIME
  2968. }
  2969. LCD_MESSAGERPGM(MSG_HEATING_COMPLETE);
  2970. heating_status = 2;
  2971. if (farm_mode) { prusa_statistics(2); };
  2972. starttime=millis();
  2973. previous_millis_cmd = millis();
  2974. }
  2975. break;
  2976. case 190: // M190 - Wait for bed heater to reach target.
  2977. #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
  2978. LCD_MESSAGERPGM(MSG_BED_HEATING);
  2979. heating_status = 3;
  2980. if (farm_mode) { prusa_statistics(1); };
  2981. if (code_seen('S'))
  2982. {
  2983. setTargetBed(code_value());
  2984. CooldownNoWait = true;
  2985. }
  2986. else if (code_seen('R'))
  2987. {
  2988. setTargetBed(code_value());
  2989. CooldownNoWait = false;
  2990. }
  2991. codenum = millis();
  2992. cancel_heatup = false;
  2993. target_direction = isHeatingBed(); // true if heating, false if cooling
  2994. while ( (target_direction)&&(!cancel_heatup) ? (isHeatingBed()) : (isCoolingBed()&&(CooldownNoWait==false)) )
  2995. {
  2996. if(( millis() - codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
  2997. {
  2998. float tt=degHotend(active_extruder);
  2999. SERIAL_PROTOCOLPGM("T:");
  3000. SERIAL_PROTOCOL(tt);
  3001. SERIAL_PROTOCOLPGM(" E:");
  3002. SERIAL_PROTOCOL((int)active_extruder);
  3003. SERIAL_PROTOCOLPGM(" B:");
  3004. SERIAL_PROTOCOL_F(degBed(),1);
  3005. SERIAL_PROTOCOLLN("");
  3006. codenum = millis();
  3007. }
  3008. manage_heater();
  3009. manage_inactivity();
  3010. lcd_update();
  3011. }
  3012. LCD_MESSAGERPGM(MSG_BED_DONE);
  3013. heating_status = 4;
  3014. previous_millis_cmd = millis();
  3015. #endif
  3016. break;
  3017. #if defined(FAN_PIN) && FAN_PIN > -1
  3018. case 106: //M106 Fan On
  3019. if (code_seen('S')){
  3020. fanSpeed=constrain(code_value(),0,255);
  3021. }
  3022. else {
  3023. fanSpeed=255;
  3024. }
  3025. break;
  3026. case 107: //M107 Fan Off
  3027. fanSpeed = 0;
  3028. break;
  3029. #endif //FAN_PIN
  3030. #if defined(PS_ON_PIN) && PS_ON_PIN > -1
  3031. case 80: // M80 - Turn on Power Supply
  3032. SET_OUTPUT(PS_ON_PIN); //GND
  3033. WRITE(PS_ON_PIN, PS_ON_AWAKE);
  3034. // If you have a switch on suicide pin, this is useful
  3035. // if you want to start another print with suicide feature after
  3036. // a print without suicide...
  3037. #if defined SUICIDE_PIN && SUICIDE_PIN > -1
  3038. SET_OUTPUT(SUICIDE_PIN);
  3039. WRITE(SUICIDE_PIN, HIGH);
  3040. #endif
  3041. #ifdef ULTIPANEL
  3042. powersupply = true;
  3043. LCD_MESSAGERPGM(WELCOME_MSG);
  3044. lcd_update();
  3045. #endif
  3046. break;
  3047. #endif
  3048. case 81: // M81 - Turn off Power Supply
  3049. disable_heater();
  3050. st_synchronize();
  3051. disable_e0();
  3052. disable_e1();
  3053. disable_e2();
  3054. finishAndDisableSteppers();
  3055. fanSpeed = 0;
  3056. delay(1000); // Wait a little before to switch off
  3057. #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
  3058. st_synchronize();
  3059. suicide();
  3060. #elif defined(PS_ON_PIN) && PS_ON_PIN > -1
  3061. SET_OUTPUT(PS_ON_PIN);
  3062. WRITE(PS_ON_PIN, PS_ON_ASLEEP);
  3063. #endif
  3064. #ifdef ULTIPANEL
  3065. powersupply = false;
  3066. LCD_MESSAGERPGM(CAT4(CUSTOM_MENDEL_NAME,PSTR(" "),MSG_OFF,PSTR("."))); //!!
  3067. /*
  3068. MACHNAME = "Prusa i3"
  3069. MSGOFF = "Vypnuto"
  3070. "Prusai3"" ""vypnuto""."
  3071. "Prusa i3"" "MSG_ALL[lang_selected][50]"."
  3072. */
  3073. lcd_update();
  3074. #endif
  3075. break;
  3076. case 82:
  3077. axis_relative_modes[3] = false;
  3078. break;
  3079. case 83:
  3080. axis_relative_modes[3] = true;
  3081. break;
  3082. case 18: //compatibility
  3083. case 84: // M84
  3084. if(code_seen('S')){
  3085. stepper_inactive_time = code_value() * 1000;
  3086. }
  3087. else
  3088. {
  3089. 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])));
  3090. if(all_axis)
  3091. {
  3092. st_synchronize();
  3093. disable_e0();
  3094. disable_e1();
  3095. disable_e2();
  3096. finishAndDisableSteppers();
  3097. }
  3098. else
  3099. {
  3100. st_synchronize();
  3101. if(code_seen('X')) disable_x();
  3102. if(code_seen('Y')) disable_y();
  3103. if(code_seen('Z')) disable_z();
  3104. #if ((E0_ENABLE_PIN != X_ENABLE_PIN) && (E1_ENABLE_PIN != Y_ENABLE_PIN)) // Only enable on boards that have seperate ENABLE_PINS
  3105. if(code_seen('E')) {
  3106. disable_e0();
  3107. disable_e1();
  3108. disable_e2();
  3109. }
  3110. #endif
  3111. }
  3112. }
  3113. break;
  3114. case 85: // M85
  3115. if(code_seen('S')) {
  3116. max_inactive_time = code_value() * 1000;
  3117. }
  3118. break;
  3119. case 92: // M92
  3120. for(int8_t i=0; i < NUM_AXIS; i++)
  3121. {
  3122. if(code_seen(axis_codes[i]))
  3123. {
  3124. if(i == 3) { // E
  3125. float value = code_value();
  3126. if(value < 20.0) {
  3127. float factor = axis_steps_per_unit[i] / value; // increase e constants if M92 E14 is given for netfab.
  3128. max_jerk[E_AXIS] *= factor;
  3129. max_feedrate[i] *= factor;
  3130. axis_steps_per_sqr_second[i] *= factor;
  3131. }
  3132. axis_steps_per_unit[i] = value;
  3133. }
  3134. else {
  3135. axis_steps_per_unit[i] = code_value();
  3136. }
  3137. }
  3138. }
  3139. break;
  3140. case 115: // M115
  3141. if (code_seen('V')) {
  3142. // Report the Prusa version number.
  3143. SERIAL_PROTOCOLLNRPGM(FW_VERSION_STR_P());
  3144. } else if (code_seen('U')) {
  3145. // Check the firmware version provided. If the firmware version provided by the U code is higher than the currently running firmware,
  3146. // pause the print and ask the user to upgrade the firmware.
  3147. show_upgrade_dialog_if_version_newer(++ strchr_pointer);
  3148. } else {
  3149. SERIAL_PROTOCOLRPGM(MSG_M115_REPORT);
  3150. }
  3151. break;
  3152. case 117: // M117 display message
  3153. starpos = (strchr(strchr_pointer + 5,'*'));
  3154. if(starpos!=NULL)
  3155. *(starpos)='\0';
  3156. lcd_setstatus(strchr_pointer + 5);
  3157. break;
  3158. case 114: // M114
  3159. SERIAL_PROTOCOLPGM("X:");
  3160. SERIAL_PROTOCOL(current_position[X_AXIS]);
  3161. SERIAL_PROTOCOLPGM(" Y:");
  3162. SERIAL_PROTOCOL(current_position[Y_AXIS]);
  3163. SERIAL_PROTOCOLPGM(" Z:");
  3164. SERIAL_PROTOCOL(current_position[Z_AXIS]);
  3165. SERIAL_PROTOCOLPGM(" E:");
  3166. SERIAL_PROTOCOL(current_position[E_AXIS]);
  3167. SERIAL_PROTOCOLRPGM(MSG_COUNT_X);
  3168. SERIAL_PROTOCOL(float(st_get_position(X_AXIS))/axis_steps_per_unit[X_AXIS]);
  3169. SERIAL_PROTOCOLPGM(" Y:");
  3170. SERIAL_PROTOCOL(float(st_get_position(Y_AXIS))/axis_steps_per_unit[Y_AXIS]);
  3171. SERIAL_PROTOCOLPGM(" Z:");
  3172. SERIAL_PROTOCOL(float(st_get_position(Z_AXIS))/axis_steps_per_unit[Z_AXIS]);
  3173. SERIAL_PROTOCOLLN("");
  3174. break;
  3175. case 120: // M120
  3176. enable_endstops(false) ;
  3177. break;
  3178. case 121: // M121
  3179. enable_endstops(true) ;
  3180. break;
  3181. case 119: // M119
  3182. SERIAL_PROTOCOLRPGM(MSG_M119_REPORT);
  3183. SERIAL_PROTOCOLLN("");
  3184. #if defined(X_MIN_PIN) && X_MIN_PIN > -1
  3185. SERIAL_PROTOCOLRPGM(MSG_X_MIN);
  3186. if(READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING){
  3187. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
  3188. }else{
  3189. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
  3190. }
  3191. SERIAL_PROTOCOLLN("");
  3192. #endif
  3193. #if defined(X_MAX_PIN) && X_MAX_PIN > -1
  3194. SERIAL_PROTOCOLRPGM(MSG_X_MAX);
  3195. if(READ(X_MAX_PIN)^X_MAX_ENDSTOP_INVERTING){
  3196. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
  3197. }else{
  3198. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
  3199. }
  3200. SERIAL_PROTOCOLLN("");
  3201. #endif
  3202. #if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
  3203. SERIAL_PROTOCOLRPGM(MSG_Y_MIN);
  3204. if(READ(Y_MIN_PIN)^Y_MIN_ENDSTOP_INVERTING){
  3205. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
  3206. }else{
  3207. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
  3208. }
  3209. SERIAL_PROTOCOLLN("");
  3210. #endif
  3211. #if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
  3212. SERIAL_PROTOCOLRPGM(MSG_Y_MAX);
  3213. if(READ(Y_MAX_PIN)^Y_MAX_ENDSTOP_INVERTING){
  3214. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
  3215. }else{
  3216. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
  3217. }
  3218. SERIAL_PROTOCOLLN("");
  3219. #endif
  3220. #if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
  3221. SERIAL_PROTOCOLRPGM(MSG_Z_MIN);
  3222. if(READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING){
  3223. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
  3224. }else{
  3225. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
  3226. }
  3227. SERIAL_PROTOCOLLN("");
  3228. #endif
  3229. #if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
  3230. SERIAL_PROTOCOLRPGM(MSG_Z_MAX);
  3231. if(READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING){
  3232. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
  3233. }else{
  3234. SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
  3235. }
  3236. SERIAL_PROTOCOLLN("");
  3237. #endif
  3238. break;
  3239. //TODO: update for all axis, use for loop
  3240. #ifdef BLINKM
  3241. case 150: // M150
  3242. {
  3243. byte red;
  3244. byte grn;
  3245. byte blu;
  3246. if(code_seen('R')) red = code_value();
  3247. if(code_seen('U')) grn = code_value();
  3248. if(code_seen('B')) blu = code_value();
  3249. SendColors(red,grn,blu);
  3250. }
  3251. break;
  3252. #endif //BLINKM
  3253. case 200: // M200 D<millimeters> set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).
  3254. {
  3255. tmp_extruder = active_extruder;
  3256. if(code_seen('T')) {
  3257. tmp_extruder = code_value();
  3258. if(tmp_extruder >= EXTRUDERS) {
  3259. SERIAL_ECHO_START;
  3260. SERIAL_ECHO(MSG_M200_INVALID_EXTRUDER);
  3261. break;
  3262. }
  3263. }
  3264. float area = .0;
  3265. if(code_seen('D')) {
  3266. float diameter = (float)code_value();
  3267. if (diameter == 0.0) {
  3268. // setting any extruder filament size disables volumetric on the assumption that
  3269. // slicers either generate in extruder values as cubic mm or as as filament feeds
  3270. // for all extruders
  3271. volumetric_enabled = false;
  3272. } else {
  3273. filament_size[tmp_extruder] = (float)code_value();
  3274. // make sure all extruders have some sane value for the filament size
  3275. filament_size[0] = (filament_size[0] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[0]);
  3276. #if EXTRUDERS > 1
  3277. filament_size[1] = (filament_size[1] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[1]);
  3278. #if EXTRUDERS > 2
  3279. filament_size[2] = (filament_size[2] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[2]);
  3280. #endif
  3281. #endif
  3282. volumetric_enabled = true;
  3283. }
  3284. } else {
  3285. //reserved for setting filament diameter via UFID or filament measuring device
  3286. break;
  3287. }
  3288. calculate_volumetric_multipliers();
  3289. }
  3290. break;
  3291. case 201: // M201
  3292. for(int8_t i=0; i < NUM_AXIS; i++)
  3293. {
  3294. if(code_seen(axis_codes[i]))
  3295. {
  3296. max_acceleration_units_per_sq_second[i] = code_value();
  3297. }
  3298. }
  3299. // 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)
  3300. reset_acceleration_rates();
  3301. break;
  3302. #if 0 // Not used for Sprinter/grbl gen6
  3303. case 202: // M202
  3304. for(int8_t i=0; i < NUM_AXIS; i++) {
  3305. if(code_seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i];
  3306. }
  3307. break;
  3308. #endif
  3309. case 203: // M203 max feedrate mm/sec
  3310. for(int8_t i=0; i < NUM_AXIS; i++) {
  3311. if(code_seen(axis_codes[i])) max_feedrate[i] = code_value();
  3312. }
  3313. break;
  3314. case 204: // M204 acclereration S normal moves T filmanent only moves
  3315. {
  3316. if(code_seen('S')) acceleration = code_value() ;
  3317. if(code_seen('T')) retract_acceleration = code_value() ;
  3318. }
  3319. break;
  3320. 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
  3321. {
  3322. if(code_seen('S')) minimumfeedrate = code_value();
  3323. if(code_seen('T')) mintravelfeedrate = code_value();
  3324. if(code_seen('B')) minsegmenttime = code_value() ;
  3325. if(code_seen('X')) max_jerk[X_AXIS] = max_jerk[Y_AXIS] = code_value();
  3326. if(code_seen('Y')) max_jerk[Y_AXIS] = code_value();
  3327. if(code_seen('Z')) max_jerk[Z_AXIS] = code_value();
  3328. if(code_seen('E')) max_jerk[E_AXIS] = code_value();
  3329. }
  3330. break;
  3331. case 206: // M206 additional homing offset
  3332. for(int8_t i=0; i < 3; i++)
  3333. {
  3334. if(code_seen(axis_codes[i])) add_homing[i] = code_value();
  3335. }
  3336. break;
  3337. #ifdef FWRETRACT
  3338. case 207: //M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop]
  3339. {
  3340. if(code_seen('S'))
  3341. {
  3342. retract_length = code_value() ;
  3343. }
  3344. if(code_seen('F'))
  3345. {
  3346. retract_feedrate = code_value()/60 ;
  3347. }
  3348. if(code_seen('Z'))
  3349. {
  3350. retract_zlift = code_value() ;
  3351. }
  3352. }break;
  3353. case 208: // M208 - set retract recover length S[positive mm surplus to the M207 S*] F[feedrate mm/min]
  3354. {
  3355. if(code_seen('S'))
  3356. {
  3357. retract_recover_length = code_value() ;
  3358. }
  3359. if(code_seen('F'))
  3360. {
  3361. retract_recover_feedrate = code_value()/60 ;
  3362. }
  3363. }break;
  3364. 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.
  3365. {
  3366. if(code_seen('S'))
  3367. {
  3368. int t= code_value() ;
  3369. switch(t)
  3370. {
  3371. case 0:
  3372. {
  3373. autoretract_enabled=false;
  3374. retracted[0]=false;
  3375. #if EXTRUDERS > 1
  3376. retracted[1]=false;
  3377. #endif
  3378. #if EXTRUDERS > 2
  3379. retracted[2]=false;
  3380. #endif
  3381. }break;
  3382. case 1:
  3383. {
  3384. autoretract_enabled=true;
  3385. retracted[0]=false;
  3386. #if EXTRUDERS > 1
  3387. retracted[1]=false;
  3388. #endif
  3389. #if EXTRUDERS > 2
  3390. retracted[2]=false;
  3391. #endif
  3392. }break;
  3393. default:
  3394. SERIAL_ECHO_START;
  3395. SERIAL_ECHORPGM(MSG_UNKNOWN_COMMAND);
  3396. SERIAL_ECHO(CMDBUFFER_CURRENT_STRING);
  3397. SERIAL_ECHOLNPGM("\"");
  3398. }
  3399. }
  3400. }break;
  3401. #endif // FWRETRACT
  3402. #if EXTRUDERS > 1
  3403. case 218: // M218 - set hotend offset (in mm), T<extruder_number> X<offset_on_X> Y<offset_on_Y>
  3404. {
  3405. if(setTargetedHotend(218)){
  3406. break;
  3407. }
  3408. if(code_seen('X'))
  3409. {
  3410. extruder_offset[X_AXIS][tmp_extruder] = code_value();
  3411. }
  3412. if(code_seen('Y'))
  3413. {
  3414. extruder_offset[Y_AXIS][tmp_extruder] = code_value();
  3415. }
  3416. SERIAL_ECHO_START;
  3417. SERIAL_ECHORPGM(MSG_HOTEND_OFFSET);
  3418. for(tmp_extruder = 0; tmp_extruder < EXTRUDERS; tmp_extruder++)
  3419. {
  3420. SERIAL_ECHO(" ");
  3421. SERIAL_ECHO(extruder_offset[X_AXIS][tmp_extruder]);
  3422. SERIAL_ECHO(",");
  3423. SERIAL_ECHO(extruder_offset[Y_AXIS][tmp_extruder]);
  3424. }
  3425. SERIAL_ECHOLN("");
  3426. }break;
  3427. #endif
  3428. case 220: // M220 S<factor in percent>- set speed factor override percentage
  3429. {
  3430. if(code_seen('S'))
  3431. {
  3432. feedmultiply = code_value() ;
  3433. }
  3434. }
  3435. break;
  3436. case 221: // M221 S<factor in percent>- set extrude factor override percentage
  3437. {
  3438. if(code_seen('S'))
  3439. {
  3440. int tmp_code = code_value();
  3441. if (code_seen('T'))
  3442. {
  3443. if(setTargetedHotend(221)){
  3444. break;
  3445. }
  3446. extruder_multiply[tmp_extruder] = tmp_code;
  3447. }
  3448. else
  3449. {
  3450. extrudemultiply = tmp_code ;
  3451. }
  3452. }
  3453. }
  3454. break;
  3455. case 226: // M226 P<pin number> S<pin state>- Wait until the specified pin reaches the state required
  3456. {
  3457. if(code_seen('P')){
  3458. int pin_number = code_value(); // pin number
  3459. int pin_state = -1; // required pin state - default is inverted
  3460. if(code_seen('S')) pin_state = code_value(); // required pin state
  3461. if(pin_state >= -1 && pin_state <= 1){
  3462. for(int8_t i = 0; i < (int8_t)(sizeof(sensitive_pins)/sizeof(int)); i++)
  3463. {
  3464. if (sensitive_pins[i] == pin_number)
  3465. {
  3466. pin_number = -1;
  3467. break;
  3468. }
  3469. }
  3470. if (pin_number > -1)
  3471. {
  3472. int target = LOW;
  3473. st_synchronize();
  3474. pinMode(pin_number, INPUT);
  3475. switch(pin_state){
  3476. case 1:
  3477. target = HIGH;
  3478. break;
  3479. case 0:
  3480. target = LOW;
  3481. break;
  3482. case -1:
  3483. target = !digitalRead(pin_number);
  3484. break;
  3485. }
  3486. while(digitalRead(pin_number) != target){
  3487. manage_heater();
  3488. manage_inactivity();
  3489. lcd_update();
  3490. }
  3491. }
  3492. }
  3493. }
  3494. }
  3495. break;
  3496. #if NUM_SERVOS > 0
  3497. case 280: // M280 - set servo position absolute. P: servo index, S: angle or microseconds
  3498. {
  3499. int servo_index = -1;
  3500. int servo_position = 0;
  3501. if (code_seen('P'))
  3502. servo_index = code_value();
  3503. if (code_seen('S')) {
  3504. servo_position = code_value();
  3505. if ((servo_index >= 0) && (servo_index < NUM_SERVOS)) {
  3506. #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
  3507. servos[servo_index].attach(0);
  3508. #endif
  3509. servos[servo_index].write(servo_position);
  3510. #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
  3511. delay(PROBE_SERVO_DEACTIVATION_DELAY);
  3512. servos[servo_index].detach();
  3513. #endif
  3514. }
  3515. else {
  3516. SERIAL_ECHO_START;
  3517. SERIAL_ECHO("Servo ");
  3518. SERIAL_ECHO(servo_index);
  3519. SERIAL_ECHOLN(" out of range");
  3520. }
  3521. }
  3522. else if (servo_index >= 0) {
  3523. SERIAL_PROTOCOL(MSG_OK);
  3524. SERIAL_PROTOCOL(" Servo ");
  3525. SERIAL_PROTOCOL(servo_index);
  3526. SERIAL_PROTOCOL(": ");
  3527. SERIAL_PROTOCOL(servos[servo_index].read());
  3528. SERIAL_PROTOCOLLN("");
  3529. }
  3530. }
  3531. break;
  3532. #endif // NUM_SERVOS > 0
  3533. #if (LARGE_FLASH == true && ( BEEPER > 0 || defined(ULTRALCD) || defined(LCD_USE_I2C_BUZZER)))
  3534. case 300: // M300
  3535. {
  3536. int beepS = code_seen('S') ? code_value() : 110;
  3537. int beepP = code_seen('P') ? code_value() : 1000;
  3538. if (beepS > 0)
  3539. {
  3540. #if BEEPER > 0
  3541. tone(BEEPER, beepS);
  3542. delay(beepP);
  3543. noTone(BEEPER);
  3544. #elif defined(ULTRALCD)
  3545. lcd_buzz(beepS, beepP);
  3546. #elif defined(LCD_USE_I2C_BUZZER)
  3547. lcd_buzz(beepP, beepS);
  3548. #endif
  3549. }
  3550. else
  3551. {
  3552. delay(beepP);
  3553. }
  3554. }
  3555. break;
  3556. #endif // M300
  3557. #ifdef PIDTEMP
  3558. case 301: // M301
  3559. {
  3560. if(code_seen('P')) Kp = code_value();
  3561. if(code_seen('I')) Ki = scalePID_i(code_value());
  3562. if(code_seen('D')) Kd = scalePID_d(code_value());
  3563. #ifdef PID_ADD_EXTRUSION_RATE
  3564. if(code_seen('C')) Kc = code_value();
  3565. #endif
  3566. updatePID();
  3567. SERIAL_PROTOCOL(MSG_OK);
  3568. SERIAL_PROTOCOL(" p:");
  3569. SERIAL_PROTOCOL(Kp);
  3570. SERIAL_PROTOCOL(" i:");
  3571. SERIAL_PROTOCOL(unscalePID_i(Ki));
  3572. SERIAL_PROTOCOL(" d:");
  3573. SERIAL_PROTOCOL(unscalePID_d(Kd));
  3574. #ifdef PID_ADD_EXTRUSION_RATE
  3575. SERIAL_PROTOCOL(" c:");
  3576. //Kc does not have scaling applied above, or in resetting defaults
  3577. SERIAL_PROTOCOL(Kc);
  3578. #endif
  3579. SERIAL_PROTOCOLLN("");
  3580. }
  3581. break;
  3582. #endif //PIDTEMP
  3583. #ifdef PIDTEMPBED
  3584. case 304: // M304
  3585. {
  3586. if(code_seen('P')) bedKp = code_value();
  3587. if(code_seen('I')) bedKi = scalePID_i(code_value());
  3588. if(code_seen('D')) bedKd = scalePID_d(code_value());
  3589. updatePID();
  3590. SERIAL_PROTOCOL(MSG_OK);
  3591. SERIAL_PROTOCOL(" p:");
  3592. SERIAL_PROTOCOL(bedKp);
  3593. SERIAL_PROTOCOL(" i:");
  3594. SERIAL_PROTOCOL(unscalePID_i(bedKi));
  3595. SERIAL_PROTOCOL(" d:");
  3596. SERIAL_PROTOCOL(unscalePID_d(bedKd));
  3597. SERIAL_PROTOCOLLN("");
  3598. }
  3599. break;
  3600. #endif //PIDTEMP
  3601. case 240: // M240 Triggers a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/
  3602. {
  3603. #ifdef CHDK
  3604. SET_OUTPUT(CHDK);
  3605. WRITE(CHDK, HIGH);
  3606. chdkHigh = millis();
  3607. chdkActive = true;
  3608. #else
  3609. #if defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1
  3610. const uint8_t NUM_PULSES=16;
  3611. const float PULSE_LENGTH=0.01524;
  3612. for(int i=0; i < NUM_PULSES; i++) {
  3613. WRITE(PHOTOGRAPH_PIN, HIGH);
  3614. _delay_ms(PULSE_LENGTH);
  3615. WRITE(PHOTOGRAPH_PIN, LOW);
  3616. _delay_ms(PULSE_LENGTH);
  3617. }
  3618. delay(7.33);
  3619. for(int i=0; i < NUM_PULSES; i++) {
  3620. WRITE(PHOTOGRAPH_PIN, HIGH);
  3621. _delay_ms(PULSE_LENGTH);
  3622. WRITE(PHOTOGRAPH_PIN, LOW);
  3623. _delay_ms(PULSE_LENGTH);
  3624. }
  3625. #endif
  3626. #endif //chdk end if
  3627. }
  3628. break;
  3629. #ifdef DOGLCD
  3630. case 250: // M250 Set LCD contrast value: C<value> (value 0..63)
  3631. {
  3632. if (code_seen('C')) {
  3633. lcd_setcontrast( ((int)code_value())&63 );
  3634. }
  3635. SERIAL_PROTOCOLPGM("lcd contrast value: ");
  3636. SERIAL_PROTOCOL(lcd_contrast);
  3637. SERIAL_PROTOCOLLN("");
  3638. }
  3639. break;
  3640. #endif
  3641. #ifdef PREVENT_DANGEROUS_EXTRUDE
  3642. case 302: // allow cold extrudes, or set the minimum extrude temperature
  3643. {
  3644. float temp = .0;
  3645. if (code_seen('S')) temp=code_value();
  3646. set_extrude_min_temp(temp);
  3647. }
  3648. break;
  3649. #endif
  3650. case 303: // M303 PID autotune
  3651. {
  3652. float temp = 150.0;
  3653. int e=0;
  3654. int c=5;
  3655. if (code_seen('E')) e=code_value();
  3656. if (e<0)
  3657. temp=70;
  3658. if (code_seen('S')) temp=code_value();
  3659. if (code_seen('C')) c=code_value();
  3660. PID_autotune(temp, e, c);
  3661. }
  3662. break;
  3663. case 400: // M400 finish all moves
  3664. {
  3665. st_synchronize();
  3666. }
  3667. break;
  3668. #ifdef FILAMENT_SENSOR
  3669. case 404: //M404 Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or display nominal filament width
  3670. {
  3671. #if (FILWIDTH_PIN > -1)
  3672. if(code_seen('N')) filament_width_nominal=code_value();
  3673. else{
  3674. SERIAL_PROTOCOLPGM("Filament dia (nominal mm):");
  3675. SERIAL_PROTOCOLLN(filament_width_nominal);
  3676. }
  3677. #endif
  3678. }
  3679. break;
  3680. case 405: //M405 Turn on filament sensor for control
  3681. {
  3682. if(code_seen('D')) meas_delay_cm=code_value();
  3683. if(meas_delay_cm> MAX_MEASUREMENT_DELAY)
  3684. meas_delay_cm = MAX_MEASUREMENT_DELAY;
  3685. if(delay_index2 == -1) //initialize the ring buffer if it has not been done since startup
  3686. {
  3687. int temp_ratio = widthFil_to_size_ratio();
  3688. for (delay_index1=0; delay_index1<(MAX_MEASUREMENT_DELAY+1); ++delay_index1 ){
  3689. measurement_delay[delay_index1]=temp_ratio-100; //subtract 100 to scale within a signed byte
  3690. }
  3691. delay_index1=0;
  3692. delay_index2=0;
  3693. }
  3694. filament_sensor = true ;
  3695. //SERIAL_PROTOCOLPGM("Filament dia (measured mm):");
  3696. //SERIAL_PROTOCOL(filament_width_meas);
  3697. //SERIAL_PROTOCOLPGM("Extrusion ratio(%):");
  3698. //SERIAL_PROTOCOL(extrudemultiply);
  3699. }
  3700. break;
  3701. case 406: //M406 Turn off filament sensor for control
  3702. {
  3703. filament_sensor = false ;
  3704. }
  3705. break;
  3706. case 407: //M407 Display measured filament diameter
  3707. {
  3708. SERIAL_PROTOCOLPGM("Filament dia (measured mm):");
  3709. SERIAL_PROTOCOLLN(filament_width_meas);
  3710. }
  3711. break;
  3712. #endif
  3713. case 500: // M500 Store settings in EEPROM
  3714. {
  3715. Config_StoreSettings();
  3716. }
  3717. break;
  3718. case 501: // M501 Read settings from EEPROM
  3719. {
  3720. Config_RetrieveSettings();
  3721. }
  3722. break;
  3723. case 502: // M502 Revert to default settings
  3724. {
  3725. Config_ResetDefault();
  3726. }
  3727. break;
  3728. case 503: // M503 print settings currently in memory
  3729. {
  3730. Config_PrintSettings();
  3731. }
  3732. break;
  3733. case 509: //M509 Force language selection
  3734. {
  3735. lcd_force_language_selection();
  3736. SERIAL_ECHO_START;
  3737. SERIAL_PROTOCOLPGM(("LANG SEL FORCED"));
  3738. }
  3739. break;
  3740. #ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
  3741. case 540:
  3742. {
  3743. if(code_seen('S')) abort_on_endstop_hit = code_value() > 0;
  3744. }
  3745. break;
  3746. #endif
  3747. #ifdef CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
  3748. case CUSTOM_M_CODE_SET_Z_PROBE_OFFSET:
  3749. {
  3750. float value;
  3751. if (code_seen('Z'))
  3752. {
  3753. value = code_value();
  3754. if ((Z_PROBE_OFFSET_RANGE_MIN <= value) && (value <= Z_PROBE_OFFSET_RANGE_MAX))
  3755. {
  3756. zprobe_zoffset = -value; // compare w/ line 278 of ConfigurationStore.cpp
  3757. SERIAL_ECHO_START;
  3758. SERIAL_ECHOLNRPGM(CAT4(MSG_ZPROBE_ZOFFSET, " ", MSG_OK,PSTR("")));
  3759. SERIAL_PROTOCOLLN("");
  3760. }
  3761. else
  3762. {
  3763. SERIAL_ECHO_START;
  3764. SERIAL_ECHORPGM(MSG_ZPROBE_ZOFFSET);
  3765. SERIAL_ECHORPGM(MSG_Z_MIN);
  3766. SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MIN);
  3767. SERIAL_ECHORPGM(MSG_Z_MAX);
  3768. SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MAX);
  3769. SERIAL_PROTOCOLLN("");
  3770. }
  3771. }
  3772. else
  3773. {
  3774. SERIAL_ECHO_START;
  3775. SERIAL_ECHOLNRPGM(CAT2(MSG_ZPROBE_ZOFFSET, PSTR(" : ")));
  3776. SERIAL_ECHO(-zprobe_zoffset);
  3777. SERIAL_PROTOCOLLN("");
  3778. }
  3779. break;
  3780. }
  3781. #endif // CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
  3782. #ifdef FILAMENTCHANGEENABLE
  3783. case 600: //Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
  3784. {
  3785. st_synchronize();
  3786. feedmultiplyBckp=feedmultiply;
  3787. int8_t TooLowZ = 0;
  3788. float target[4];
  3789. float lastpos[4];
  3790. target[X_AXIS]=current_position[X_AXIS];
  3791. target[Y_AXIS]=current_position[Y_AXIS];
  3792. target[Z_AXIS]=current_position[Z_AXIS];
  3793. target[E_AXIS]=current_position[E_AXIS];
  3794. lastpos[X_AXIS]=current_position[X_AXIS];
  3795. lastpos[Y_AXIS]=current_position[Y_AXIS];
  3796. lastpos[Z_AXIS]=current_position[Z_AXIS];
  3797. lastpos[E_AXIS]=current_position[E_AXIS];
  3798. //Restract extruder
  3799. if(code_seen('E'))
  3800. {
  3801. target[E_AXIS]+= code_value();
  3802. }
  3803. else
  3804. {
  3805. #ifdef FILAMENTCHANGE_FIRSTRETRACT
  3806. target[E_AXIS]+= FILAMENTCHANGE_FIRSTRETRACT ;
  3807. #endif
  3808. }
  3809. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder);
  3810. //Lift Z
  3811. if(code_seen('Z'))
  3812. {
  3813. target[Z_AXIS]+= code_value();
  3814. }
  3815. else
  3816. {
  3817. #ifdef FILAMENTCHANGE_ZADD
  3818. target[Z_AXIS]+= FILAMENTCHANGE_ZADD ;
  3819. if(target[Z_AXIS] < 10){
  3820. target[Z_AXIS]+= 10 ;
  3821. TooLowZ = 1;
  3822. }else{
  3823. TooLowZ = 0;
  3824. }
  3825. #endif
  3826. }
  3827. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_ZFEED, active_extruder);
  3828. //Move XY to side
  3829. if(code_seen('X'))
  3830. {
  3831. target[X_AXIS]+= code_value();
  3832. }
  3833. else
  3834. {
  3835. #ifdef FILAMENTCHANGE_XPOS
  3836. target[X_AXIS]= FILAMENTCHANGE_XPOS ;
  3837. #endif
  3838. }
  3839. if(code_seen('Y'))
  3840. {
  3841. target[Y_AXIS]= code_value();
  3842. }
  3843. else
  3844. {
  3845. #ifdef FILAMENTCHANGE_YPOS
  3846. target[Y_AXIS]= FILAMENTCHANGE_YPOS ;
  3847. #endif
  3848. }
  3849. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_XYFEED, active_extruder);
  3850. // Unload filament
  3851. if(code_seen('L'))
  3852. {
  3853. target[E_AXIS]+= code_value();
  3854. }
  3855. else
  3856. {
  3857. #ifdef FILAMENTCHANGE_FINALRETRACT
  3858. target[E_AXIS]+= FILAMENTCHANGE_FINALRETRACT ;
  3859. #endif
  3860. }
  3861. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder);
  3862. //finish moves
  3863. st_synchronize();
  3864. //disable extruder steppers so filament can be removed
  3865. disable_e0();
  3866. disable_e1();
  3867. disable_e2();
  3868. delay(100);
  3869. //Wait for user to insert filament
  3870. uint8_t cnt=0;
  3871. int counterBeep = 0;
  3872. lcd_wait_interact();
  3873. while(!lcd_clicked()){
  3874. cnt++;
  3875. manage_heater();
  3876. manage_inactivity(true);
  3877. if(cnt==0)
  3878. {
  3879. #if BEEPER > 0
  3880. if (counterBeep== 500){
  3881. counterBeep = 0;
  3882. }
  3883. SET_OUTPUT(BEEPER);
  3884. if (counterBeep== 0){
  3885. WRITE(BEEPER,HIGH);
  3886. }
  3887. if (counterBeep== 20){
  3888. WRITE(BEEPER,LOW);
  3889. }
  3890. counterBeep++;
  3891. #else
  3892. #if !defined(LCD_FEEDBACK_FREQUENCY_HZ) || !defined(LCD_FEEDBACK_FREQUENCY_DURATION_MS)
  3893. lcd_buzz(1000/6,100);
  3894. #else
  3895. lcd_buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS,LCD_FEEDBACK_FREQUENCY_HZ);
  3896. #endif
  3897. #endif
  3898. }
  3899. }
  3900. //Filament inserted
  3901. WRITE(BEEPER,LOW);
  3902. //Feed the filament to the end of nozzle quickly
  3903. target[E_AXIS]+= FILAMENTCHANGE_FIRSTFEED ;
  3904. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EFEED, active_extruder);
  3905. //Extrude some filament
  3906. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  3907. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EXFEED, active_extruder);
  3908. //Wait for user to check the state
  3909. lcd_change_fil_state = 0;
  3910. lcd_loading_filament();
  3911. while ((lcd_change_fil_state == 0)||(lcd_change_fil_state != 1)){
  3912. lcd_change_fil_state = 0;
  3913. lcd_alright();
  3914. switch(lcd_change_fil_state){
  3915. // Filament failed to load so load it again
  3916. case 2:
  3917. target[E_AXIS]+= FILAMENTCHANGE_FIRSTFEED ;
  3918. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EFEED, active_extruder);
  3919. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  3920. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EXFEED, active_extruder);
  3921. lcd_loading_filament();
  3922. break;
  3923. // Filament loaded properly but color is not clear
  3924. case 3:
  3925. target[E_AXIS]+= FILAMENTCHANGE_FINALFEED ;
  3926. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 2, active_extruder);
  3927. lcd_loading_color();
  3928. break;
  3929. // Everything good
  3930. default:
  3931. lcd_change_success();
  3932. break;
  3933. }
  3934. }
  3935. //Not let's go back to print
  3936. //Feed a little of filament to stabilize pressure
  3937. target[E_AXIS]+= FILAMENTCHANGE_RECFEED;
  3938. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_EXFEED, active_extruder);
  3939. //Retract
  3940. target[E_AXIS]+= FILAMENTCHANGE_FIRSTRETRACT;
  3941. plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder);
  3942. //plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 70, active_extruder); //should do nothing
  3943. //Move XY back
  3944. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], target[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_XYFEED, active_extruder);
  3945. //Move Z back
  3946. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_ZFEED, active_extruder);
  3947. target[E_AXIS]= target[E_AXIS] - FILAMENTCHANGE_FIRSTRETRACT;
  3948. //Unretract
  3949. plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], target[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder);
  3950. //Set E position to original
  3951. plan_set_e_position(lastpos[E_AXIS]);
  3952. //Recover feed rate
  3953. feedmultiply=feedmultiplyBckp;
  3954. char cmd[9];
  3955. sprintf_P(cmd, PSTR("M220 S%i"), feedmultiplyBckp);
  3956. enquecommand(cmd);
  3957. }
  3958. break;
  3959. #endif //FILAMENTCHANGEENABLE
  3960. case 907: // M907 Set digital trimpot motor current using axis codes.
  3961. {
  3962. #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
  3963. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) digipot_current(i,code_value());
  3964. if(code_seen('B')) digipot_current(4,code_value());
  3965. if(code_seen('S')) for(int i=0;i<=4;i++) digipot_current(i,code_value());
  3966. #endif
  3967. #ifdef MOTOR_CURRENT_PWM_XY_PIN
  3968. if(code_seen('X')) digipot_current(0, code_value());
  3969. #endif
  3970. #ifdef MOTOR_CURRENT_PWM_Z_PIN
  3971. if(code_seen('Z')) digipot_current(1, code_value());
  3972. #endif
  3973. #ifdef MOTOR_CURRENT_PWM_E_PIN
  3974. if(code_seen('E')) digipot_current(2, code_value());
  3975. #endif
  3976. #ifdef DIGIPOT_I2C
  3977. // this one uses actual amps in floating point
  3978. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) digipot_i2c_set_current(i, code_value());
  3979. // for each additional extruder (named B,C,D,E..., channels 4,5,6,7...)
  3980. for(int i=NUM_AXIS;i<DIGIPOT_I2C_NUM_CHANNELS;i++) if(code_seen('B'+i-NUM_AXIS)) digipot_i2c_set_current(i, code_value());
  3981. #endif
  3982. }
  3983. break;
  3984. case 908: // M908 Control digital trimpot directly.
  3985. {
  3986. #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
  3987. uint8_t channel,current;
  3988. if(code_seen('P')) channel=code_value();
  3989. if(code_seen('S')) current=code_value();
  3990. digitalPotWrite(channel, current);
  3991. #endif
  3992. }
  3993. break;
  3994. case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
  3995. {
  3996. #if defined(X_MS1_PIN) && X_MS1_PIN > -1
  3997. if(code_seen('S')) for(int i=0;i<=4;i++) microstep_mode(i,code_value());
  3998. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_mode(i,(uint8_t)code_value());
  3999. if(code_seen('B')) microstep_mode(4,code_value());
  4000. microstep_readings();
  4001. #endif
  4002. }
  4003. break;
  4004. case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low.
  4005. {
  4006. #if defined(X_MS1_PIN) && X_MS1_PIN > -1
  4007. if(code_seen('S')) switch((int)code_value())
  4008. {
  4009. case 1:
  4010. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_ms(i,code_value(),-1);
  4011. if(code_seen('B')) microstep_ms(4,code_value(),-1);
  4012. break;
  4013. case 2:
  4014. for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_ms(i,-1,code_value());
  4015. if(code_seen('B')) microstep_ms(4,-1,code_value());
  4016. break;
  4017. }
  4018. microstep_readings();
  4019. #endif
  4020. }
  4021. break;
  4022. case 999: // M999: Restart after being stopped
  4023. Stopped = false;
  4024. lcd_reset_alert_level();
  4025. gcode_LastN = Stopped_gcode_LastN;
  4026. FlushSerialRequestResend();
  4027. break;
  4028. }
  4029. } // end if(code_seen('M')) (end of M codes)
  4030. else if(code_seen('T'))
  4031. {
  4032. tmp_extruder = code_value();
  4033. if(tmp_extruder >= EXTRUDERS) {
  4034. SERIAL_ECHO_START;
  4035. SERIAL_ECHO("T");
  4036. SERIAL_ECHO(tmp_extruder);
  4037. SERIAL_ECHOLN(MSG_INVALID_EXTRUDER);
  4038. }
  4039. else {
  4040. boolean make_move = false;
  4041. if(code_seen('F')) {
  4042. make_move = true;
  4043. next_feedrate = code_value();
  4044. if(next_feedrate > 0.0) {
  4045. feedrate = next_feedrate;
  4046. }
  4047. }
  4048. #if EXTRUDERS > 1
  4049. if(tmp_extruder != active_extruder) {
  4050. // Save current position to return to after applying extruder offset
  4051. memcpy(destination, current_position, sizeof(destination));
  4052. // Offset extruder (only by XY)
  4053. int i;
  4054. for(i = 0; i < 2; i++) {
  4055. current_position[i] = current_position[i] -
  4056. extruder_offset[i][active_extruder] +
  4057. extruder_offset[i][tmp_extruder];
  4058. }
  4059. // Set the new active extruder and position
  4060. active_extruder = tmp_extruder;
  4061. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
  4062. // Move to the old position if 'F' was in the parameters
  4063. if(make_move && Stopped == false) {
  4064. prepare_move();
  4065. }
  4066. }
  4067. #endif
  4068. SERIAL_ECHO_START;
  4069. SERIAL_ECHO(MSG_ACTIVE_EXTRUDER);
  4070. SERIAL_PROTOCOLLN((int)active_extruder);
  4071. }
  4072. } // end if(code_seen('T')) (end of T codes)
  4073. else
  4074. {
  4075. SERIAL_ECHO_START;
  4076. SERIAL_ECHORPGM(MSG_UNKNOWN_COMMAND);
  4077. SERIAL_ECHO(CMDBUFFER_CURRENT_STRING);
  4078. SERIAL_ECHOLNPGM("\"");
  4079. }
  4080. ClearToSend();
  4081. }
  4082. void FlushSerialRequestResend()
  4083. {
  4084. //char cmdbuffer[bufindr][100]="Resend:";
  4085. MYSERIAL.flush();
  4086. SERIAL_PROTOCOLRPGM(MSG_RESEND);
  4087. SERIAL_PROTOCOLLN(gcode_LastN + 1);
  4088. ClearToSend();
  4089. }
  4090. // Confirm the execution of a command, if sent from a serial line.
  4091. // Execution of a command from a SD card will not be confirmed.
  4092. void ClearToSend()
  4093. {
  4094. previous_millis_cmd = millis();
  4095. if (CMDBUFFER_CURRENT_TYPE == CMDBUFFER_CURRENT_TYPE_USB)
  4096. SERIAL_PROTOCOLLNRPGM(MSG_OK);
  4097. }
  4098. void get_coordinates()
  4099. {
  4100. bool seen[4]={false,false,false,false};
  4101. for(int8_t i=0; i < NUM_AXIS; i++) {
  4102. if(code_seen(axis_codes[i]))
  4103. {
  4104. destination[i] = (float)code_value() + (axis_relative_modes[i] || relative_mode)*current_position[i];
  4105. seen[i]=true;
  4106. }
  4107. else destination[i] = current_position[i]; //Are these else lines really needed?
  4108. }
  4109. if(code_seen('F')) {
  4110. next_feedrate = code_value();
  4111. if(next_feedrate > 0.0) feedrate = next_feedrate;
  4112. }
  4113. }
  4114. void get_arc_coordinates()
  4115. {
  4116. #ifdef SF_ARC_FIX
  4117. bool relative_mode_backup = relative_mode;
  4118. relative_mode = true;
  4119. #endif
  4120. get_coordinates();
  4121. #ifdef SF_ARC_FIX
  4122. relative_mode=relative_mode_backup;
  4123. #endif
  4124. if(code_seen('I')) {
  4125. offset[0] = code_value();
  4126. }
  4127. else {
  4128. offset[0] = 0.0;
  4129. }
  4130. if(code_seen('J')) {
  4131. offset[1] = code_value();
  4132. }
  4133. else {
  4134. offset[1] = 0.0;
  4135. }
  4136. }
  4137. void clamp_to_software_endstops(float target[3])
  4138. {
  4139. world2machine_clamp(target[0], target[1]);
  4140. // Clamp the Z coordinate.
  4141. if (min_software_endstops) {
  4142. float negative_z_offset = 0;
  4143. #ifdef ENABLE_AUTO_BED_LEVELING
  4144. if (Z_PROBE_OFFSET_FROM_EXTRUDER < 0) negative_z_offset = negative_z_offset + Z_PROBE_OFFSET_FROM_EXTRUDER;
  4145. if (add_homing[Z_AXIS] < 0) negative_z_offset = negative_z_offset + add_homing[Z_AXIS];
  4146. #endif
  4147. if (target[Z_AXIS] < min_pos[Z_AXIS]+negative_z_offset) target[Z_AXIS] = min_pos[Z_AXIS]+negative_z_offset;
  4148. }
  4149. if (max_software_endstops) {
  4150. if (target[Z_AXIS] > max_pos[Z_AXIS]) target[Z_AXIS] = max_pos[Z_AXIS];
  4151. }
  4152. }
  4153. #ifdef MESH_BED_LEVELING
  4154. 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) {
  4155. float dx = x - current_position[X_AXIS];
  4156. float dy = y - current_position[Y_AXIS];
  4157. float dz = z - current_position[Z_AXIS];
  4158. int n_segments = 0;
  4159. if (mbl.active) {
  4160. float len = abs(dx) + abs(dy);
  4161. if (len > 0)
  4162. // Split to 3cm segments or shorter.
  4163. n_segments = int(ceil(len / 30.f));
  4164. }
  4165. if (n_segments > 1) {
  4166. float de = e - current_position[E_AXIS];
  4167. for (int i = 1; i < n_segments; ++ i) {
  4168. float t = float(i) / float(n_segments);
  4169. plan_buffer_line(
  4170. current_position[X_AXIS] + t * dx,
  4171. current_position[Y_AXIS] + t * dy,
  4172. current_position[Z_AXIS] + t * dz,
  4173. current_position[E_AXIS] + t * de,
  4174. feed_rate, extruder);
  4175. }
  4176. }
  4177. // The rest of the path.
  4178. plan_buffer_line(x, y, z, e, feed_rate, extruder);
  4179. current_position[X_AXIS] = x;
  4180. current_position[Y_AXIS] = y;
  4181. current_position[Z_AXIS] = z;
  4182. current_position[E_AXIS] = e;
  4183. }
  4184. #endif // MESH_BED_LEVELING
  4185. void prepare_move()
  4186. {
  4187. clamp_to_software_endstops(destination);
  4188. previous_millis_cmd = millis();
  4189. // Do not use feedmultiply for E or Z only moves
  4190. if( (current_position[X_AXIS] == destination [X_AXIS]) && (current_position[Y_AXIS] == destination [Y_AXIS])) {
  4191. #ifdef MESH_BED_LEVELING
  4192. mesh_plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  4193. #else
  4194. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
  4195. #endif
  4196. }
  4197. else {
  4198. #ifdef MESH_BED_LEVELING
  4199. 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);
  4200. #else
  4201. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply*(1./(60.f*100.f)), active_extruder);
  4202. #endif
  4203. }
  4204. for(int8_t i=0; i < NUM_AXIS; i++) {
  4205. current_position[i] = destination[i];
  4206. }
  4207. }
  4208. void prepare_arc_move(char isclockwise) {
  4209. float r = hypot(offset[X_AXIS], offset[Y_AXIS]); // Compute arc radius for mc_arc
  4210. // Trace the arc
  4211. mc_arc(current_position, destination, offset, X_AXIS, Y_AXIS, Z_AXIS, feedrate*feedmultiply/60/100.0, r, isclockwise, active_extruder);
  4212. // As far as the parser is concerned, the position is now == target. In reality the
  4213. // motion control system might still be processing the action and the real tool position
  4214. // in any intermediate location.
  4215. for(int8_t i=0; i < NUM_AXIS; i++) {
  4216. current_position[i] = destination[i];
  4217. }
  4218. previous_millis_cmd = millis();
  4219. }
  4220. #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
  4221. #if defined(FAN_PIN)
  4222. #if CONTROLLERFAN_PIN == FAN_PIN
  4223. #error "You cannot set CONTROLLERFAN_PIN equal to FAN_PIN"
  4224. #endif
  4225. #endif
  4226. unsigned long lastMotor = 0; //Save the time for when a motor was turned on last
  4227. unsigned long lastMotorCheck = 0;
  4228. void controllerFan()
  4229. {
  4230. if ((millis() - lastMotorCheck) >= 2500) //Not a time critical function, so we only check every 2500ms
  4231. {
  4232. lastMotorCheck = millis();
  4233. if(!READ(X_ENABLE_PIN) || !READ(Y_ENABLE_PIN) || !READ(Z_ENABLE_PIN) || (soft_pwm_bed > 0)
  4234. #if EXTRUDERS > 2
  4235. || !READ(E2_ENABLE_PIN)
  4236. #endif
  4237. #if EXTRUDER > 1
  4238. #if defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1
  4239. || !READ(X2_ENABLE_PIN)
  4240. #endif
  4241. || !READ(E1_ENABLE_PIN)
  4242. #endif
  4243. || !READ(E0_ENABLE_PIN)) //If any of the drivers are enabled...
  4244. {
  4245. lastMotor = millis(); //... set time to NOW so the fan will turn on
  4246. }
  4247. if ((millis() - lastMotor) >= (CONTROLLERFAN_SECS*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC...
  4248. {
  4249. digitalWrite(CONTROLLERFAN_PIN, 0);
  4250. analogWrite(CONTROLLERFAN_PIN, 0);
  4251. }
  4252. else
  4253. {
  4254. // allows digital or PWM fan output to be used (see M42 handling)
  4255. digitalWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
  4256. analogWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
  4257. }
  4258. }
  4259. }
  4260. #endif
  4261. #ifdef TEMP_STAT_LEDS
  4262. static bool blue_led = false;
  4263. static bool red_led = false;
  4264. static uint32_t stat_update = 0;
  4265. void handle_status_leds(void) {
  4266. float max_temp = 0.0;
  4267. if(millis() > stat_update) {
  4268. stat_update += 500; // Update every 0.5s
  4269. for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
  4270. max_temp = max(max_temp, degHotend(cur_extruder));
  4271. max_temp = max(max_temp, degTargetHotend(cur_extruder));
  4272. }
  4273. #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
  4274. max_temp = max(max_temp, degTargetBed());
  4275. max_temp = max(max_temp, degBed());
  4276. #endif
  4277. if((max_temp > 55.0) && (red_led == false)) {
  4278. digitalWrite(STAT_LED_RED, 1);
  4279. digitalWrite(STAT_LED_BLUE, 0);
  4280. red_led = true;
  4281. blue_led = false;
  4282. }
  4283. if((max_temp < 54.0) && (blue_led == false)) {
  4284. digitalWrite(STAT_LED_RED, 0);
  4285. digitalWrite(STAT_LED_BLUE, 1);
  4286. red_led = false;
  4287. blue_led = true;
  4288. }
  4289. }
  4290. }
  4291. #endif
  4292. void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument set in Marlin.h
  4293. {
  4294. #if defined(KILL_PIN) && KILL_PIN > -1
  4295. static int killCount = 0; // make the inactivity button a bit less responsive
  4296. const int KILL_DELAY = 10000;
  4297. #endif
  4298. if(buflen < (BUFSIZE-1))
  4299. get_command();
  4300. if( (millis() - previous_millis_cmd) > max_inactive_time )
  4301. if(max_inactive_time)
  4302. kill();
  4303. if(stepper_inactive_time) {
  4304. if( (millis() - previous_millis_cmd) > stepper_inactive_time )
  4305. {
  4306. if(blocks_queued() == false && ignore_stepper_queue == false) {
  4307. disable_x();
  4308. // SERIAL_ECHOLNPGM("manage_inactivity - disable Y");
  4309. disable_y();
  4310. disable_z();
  4311. disable_e0();
  4312. disable_e1();
  4313. disable_e2();
  4314. }
  4315. }
  4316. }
  4317. #ifdef CHDK //Check if pin should be set to LOW after M240 set it to HIGH
  4318. if (chdkActive && (millis() - chdkHigh > CHDK_DELAY))
  4319. {
  4320. chdkActive = false;
  4321. WRITE(CHDK, LOW);
  4322. }
  4323. #endif
  4324. #if defined(KILL_PIN) && KILL_PIN > -1
  4325. // Check if the kill button was pressed and wait just in case it was an accidental
  4326. // key kill key press
  4327. // -------------------------------------------------------------------------------
  4328. if( 0 == READ(KILL_PIN) )
  4329. {
  4330. killCount++;
  4331. }
  4332. else if (killCount > 0)
  4333. {
  4334. killCount--;
  4335. }
  4336. // Exceeded threshold and we can confirm that it was not accidental
  4337. // KILL the machine
  4338. // ----------------------------------------------------------------
  4339. if ( killCount >= KILL_DELAY)
  4340. {
  4341. kill();
  4342. }
  4343. #endif
  4344. #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
  4345. controllerFan(); //Check if fan should be turned on to cool stepper drivers down
  4346. #endif
  4347. #ifdef EXTRUDER_RUNOUT_PREVENT
  4348. if( (millis() - previous_millis_cmd) > EXTRUDER_RUNOUT_SECONDS*1000 )
  4349. if(degHotend(active_extruder)>EXTRUDER_RUNOUT_MINTEMP)
  4350. {
  4351. bool oldstatus=READ(E0_ENABLE_PIN);
  4352. enable_e0();
  4353. float oldepos=current_position[E_AXIS];
  4354. float oldedes=destination[E_AXIS];
  4355. plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS],
  4356. destination[E_AXIS]+EXTRUDER_RUNOUT_EXTRUDE*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS],
  4357. EXTRUDER_RUNOUT_SPEED/60.*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS], active_extruder);
  4358. current_position[E_AXIS]=oldepos;
  4359. destination[E_AXIS]=oldedes;
  4360. plan_set_e_position(oldepos);
  4361. previous_millis_cmd=millis();
  4362. st_synchronize();
  4363. WRITE(E0_ENABLE_PIN,oldstatus);
  4364. }
  4365. #endif
  4366. #ifdef TEMP_STAT_LEDS
  4367. handle_status_leds();
  4368. #endif
  4369. check_axes_activity();
  4370. }
  4371. void kill(const char *full_screen_message)
  4372. {
  4373. cli(); // Stop interrupts
  4374. disable_heater();
  4375. disable_x();
  4376. // SERIAL_ECHOLNPGM("kill - disable Y");
  4377. disable_y();
  4378. disable_z();
  4379. disable_e0();
  4380. disable_e1();
  4381. disable_e2();
  4382. #if defined(PS_ON_PIN) && PS_ON_PIN > -1
  4383. pinMode(PS_ON_PIN,INPUT);
  4384. #endif
  4385. SERIAL_ERROR_START;
  4386. SERIAL_ERRORLNRPGM(MSG_ERR_KILLED);
  4387. if (full_screen_message != NULL) {
  4388. SERIAL_ERRORLNRPGM(full_screen_message);
  4389. lcd_display_message_fullscreen_P(full_screen_message);
  4390. } else {
  4391. LCD_ALERTMESSAGERPGM(MSG_KILLED);
  4392. }
  4393. // FMC small patch to update the LCD before ending
  4394. sei(); // enable interrupts
  4395. for ( int i=5; i--; lcd_update())
  4396. {
  4397. delay(200);
  4398. }
  4399. cli(); // disable interrupts
  4400. suicide();
  4401. while(1) { /* Intentionally left empty */ } // Wait for reset
  4402. }
  4403. void Stop()
  4404. {
  4405. disable_heater();
  4406. if(Stopped == false) {
  4407. Stopped = true;
  4408. Stopped_gcode_LastN = gcode_LastN; // Save last g_code for restart
  4409. SERIAL_ERROR_START;
  4410. SERIAL_ERRORLNRPGM(MSG_ERR_STOPPED);
  4411. LCD_MESSAGERPGM(MSG_STOPPED);
  4412. }
  4413. }
  4414. bool IsStopped() { return Stopped; };
  4415. #ifdef FAST_PWM_FAN
  4416. void setPwmFrequency(uint8_t pin, int val)
  4417. {
  4418. val &= 0x07;
  4419. switch(digitalPinToTimer(pin))
  4420. {
  4421. #if defined(TCCR0A)
  4422. case TIMER0A:
  4423. case TIMER0B:
  4424. // TCCR0B &= ~(_BV(CS00) | _BV(CS01) | _BV(CS02));
  4425. // TCCR0B |= val;
  4426. break;
  4427. #endif
  4428. #if defined(TCCR1A)
  4429. case TIMER1A:
  4430. case TIMER1B:
  4431. // TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
  4432. // TCCR1B |= val;
  4433. break;
  4434. #endif
  4435. #if defined(TCCR2)
  4436. case TIMER2:
  4437. case TIMER2:
  4438. TCCR2 &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
  4439. TCCR2 |= val;
  4440. break;
  4441. #endif
  4442. #if defined(TCCR2A)
  4443. case TIMER2A:
  4444. case TIMER2B:
  4445. TCCR2B &= ~(_BV(CS20) | _BV(CS21) | _BV(CS22));
  4446. TCCR2B |= val;
  4447. break;
  4448. #endif
  4449. #if defined(TCCR3A)
  4450. case TIMER3A:
  4451. case TIMER3B:
  4452. case TIMER3C:
  4453. TCCR3B &= ~(_BV(CS30) | _BV(CS31) | _BV(CS32));
  4454. TCCR3B |= val;
  4455. break;
  4456. #endif
  4457. #if defined(TCCR4A)
  4458. case TIMER4A:
  4459. case TIMER4B:
  4460. case TIMER4C:
  4461. TCCR4B &= ~(_BV(CS40) | _BV(CS41) | _BV(CS42));
  4462. TCCR4B |= val;
  4463. break;
  4464. #endif
  4465. #if defined(TCCR5A)
  4466. case TIMER5A:
  4467. case TIMER5B:
  4468. case TIMER5C:
  4469. TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52));
  4470. TCCR5B |= val;
  4471. break;
  4472. #endif
  4473. }
  4474. }
  4475. #endif //FAST_PWM_FAN
  4476. bool setTargetedHotend(int code){
  4477. tmp_extruder = active_extruder;
  4478. if(code_seen('T')) {
  4479. tmp_extruder = code_value();
  4480. if(tmp_extruder >= EXTRUDERS) {
  4481. SERIAL_ECHO_START;
  4482. switch(code){
  4483. case 104:
  4484. SERIAL_ECHO(MSG_M104_INVALID_EXTRUDER);
  4485. break;
  4486. case 105:
  4487. SERIAL_ECHO(MSG_M105_INVALID_EXTRUDER);
  4488. break;
  4489. case 109:
  4490. SERIAL_ECHO(MSG_M109_INVALID_EXTRUDER);
  4491. break;
  4492. case 218:
  4493. SERIAL_ECHO(MSG_M218_INVALID_EXTRUDER);
  4494. break;
  4495. case 221:
  4496. SERIAL_ECHO(MSG_M221_INVALID_EXTRUDER);
  4497. break;
  4498. }
  4499. SERIAL_ECHOLN(tmp_extruder);
  4500. return true;
  4501. }
  4502. }
  4503. return false;
  4504. }
  4505. void save_statistics(unsigned long _total_filament_used, unsigned long _total_print_time)
  4506. {
  4507. 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)
  4508. {
  4509. eeprom_update_dword((uint32_t *)EEPROM_TOTALTIME, 0);
  4510. eeprom_update_dword((uint32_t *)EEPROM_FILAMENTUSED, 0);
  4511. }
  4512. unsigned long _previous_filament = eeprom_read_dword((uint32_t *)EEPROM_FILAMENTUSED);
  4513. unsigned long _previous_time = eeprom_read_dword((uint32_t *)EEPROM_TOTALTIME);
  4514. eeprom_update_dword((uint32_t *)EEPROM_TOTALTIME, _previous_time + (_total_print_time/60));
  4515. eeprom_update_dword((uint32_t *)EEPROM_FILAMENTUSED, _previous_filament + (_total_filament_used / 1000));
  4516. total_filament_used = 0;
  4517. }
  4518. float calculate_volumetric_multiplier(float diameter) {
  4519. float area = .0;
  4520. float radius = .0;
  4521. radius = diameter * .5;
  4522. if (! volumetric_enabled || radius == 0) {
  4523. area = 1;
  4524. }
  4525. else {
  4526. area = M_PI * pow(radius, 2);
  4527. }
  4528. return 1.0 / area;
  4529. }
  4530. void calculate_volumetric_multipliers() {
  4531. volumetric_multiplier[0] = calculate_volumetric_multiplier(filament_size[0]);
  4532. #if EXTRUDERS > 1
  4533. volumetric_multiplier[1] = calculate_volumetric_multiplier(filament_size[1]);
  4534. #if EXTRUDERS > 2
  4535. volumetric_multiplier[2] = calculate_volumetric_multiplier(filament_size[2]);
  4536. #endif
  4537. #endif
  4538. }
  4539. void delay_keep_alive(int ms)
  4540. {
  4541. for (;;) {
  4542. manage_heater();
  4543. // Manage inactivity, but don't disable steppers on timeout.
  4544. manage_inactivity(true);
  4545. lcd_update();
  4546. if (ms == 0)
  4547. break;
  4548. else if (ms >= 50) {
  4549. delay(50);
  4550. ms -= 50;
  4551. } else {
  4552. delay(ms);
  4553. ms = 0;
  4554. }
  4555. }
  4556. }